From 6ebbd3c7e422818332cf21a7094f384959a4edca Mon Sep 17 00:00:00 2001 From: vivek-shankar Date: Thu, 14 Mar 2019 18:26:50 -0400 Subject: [PATCH] merged local gitlab version of xbeemav into github for spiri test. --- CMakeLists.txt | 33 +- README.md | 113 +-- Resources/XBee_Config.xml | 5 +- Resources/XbeeModule_DataSheet.pdf | Bin 0 -> 1014096 bytes Resources/database.xml | 31 +- include/CommunicationManager.h | 162 ++-- include/PacketsHandler.h | 293 +++--- include/SerialDevice.h | 13 +- include/XBeeSetup.h | 14 + include/frame_generators.h | 59 ++ launch/xbeemav.launch | 4 +- launch/xbeemav_test.launch | 27 + src/CommunicationManager.cpp | 864 +++++++++-------- src/PacketsHandler.cpp | 1401 +++++++++++++++++----------- src/SerialDevice.cpp | 376 ++++---- src/TestBuzz.cpp | 100 +- src/TestBuzzCyclic.cpp | 114 +++ src/XBeeSetup.cpp | 70 ++ src/Xbee.cpp | 97 +- src/frame_generators.cpp | 169 ++++ src/main.cpp | 133 +-- 21 files changed, 2440 insertions(+), 1638 deletions(-) create mode 100644 Resources/XbeeModule_DataSheet.pdf create mode 100644 include/XBeeSetup.h create mode 100644 include/frame_generators.h create mode 100644 launch/xbeemav_test.launch create mode 100644 src/TestBuzzCyclic.cpp create mode 100644 src/XBeeSetup.cpp create mode 100644 src/frame_generators.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index 0bd4af3..33b391c 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -34,12 +34,11 @@ find_package(catkin REQUIRED COMPONENTS ## catkin specific configuration ## ################################### - catkin_package( - INCLUDE_DIRS include -# LIBRARIES xbee_ros_node - CATKIN_DEPENDS roscpp std_msgs mavros_msgs -# DEPENDS system_lib +INCLUDE_DIRS include +LIBRARIES xbee_setup +CATKIN_DEPENDS roscpp std_msgs mavros_msgs +DEPENDS Boost ) ########### @@ -53,25 +52,34 @@ add_definitions( ## Specify additional locations of header files include_directories( - include ${xbee_ros_node_INCLUDE_DIRS} + include + ${xbee_ros_node_INCLUDE_DIRS} ${catkin_INCLUDE_DIRS} + ${Boost_INCLUDE_DIRS} + ${BOOST_INCLUDEDIR} ) +add_library(xbee_setup + src/XBeeSetup.cpp + src/XBeeModule.cpp + src/XMLConfigParser.cpp +) +add_executable(xbee_mav src/Xbee.cpp src/XBeeFrame.cpp src/SerialDevice.cpp src/CommunicationManager.cpp src/PacketsHandler src/frame_generators.cpp) +target_link_libraries(xbee_mav xbee_setup ${catkin_LIBRARIES}) -add_executable(xbee_mav src/Xbee.cpp src/XBeeFrame.cpp src/SerialDevice.cpp src/CommunicationManager.cpp src/PacketsHandler) -target_link_libraries(xbee_mav ${catkin_LIBRARIES}) - -add_executable(xbee_config src/main.cpp src/XBeeModule.cpp src/XMLConfigParser.cpp) -target_link_libraries(xbee_config ${catkin_LIBRARIES}) +add_executable(xbee_config src/XMLConfigParser.cpp src/main.cpp) +target_link_libraries(xbee_config xbee_setup ${catkin_LIBRARIES}) #add_executable(test_controller src/TestController.cpp) #target_link_libraries(test_controller ${catkin_LIBRARIES}) - add_executable(test_buzz src/TestBuzz.cpp) target_link_libraries(test_buzz ${catkin_LIBRARIES}) +add_executable(test_buzz_cyclic src/TestBuzzCyclic.cpp) +target_link_libraries(test_buzz_cyclic ${catkin_LIBRARIES}) + ############# ## Install ## ############# @@ -81,4 +89,3 @@ target_link_libraries(test_buzz ${catkin_LIBRARIES}) ############# ## Testing ## ############# - diff --git a/README.md b/README.md index f5d1e80..64a87c8 100644 --- a/README.md +++ b/README.md @@ -1,52 +1,43 @@ -##Description +# XbeeMav +## Description The "xbee_ros_node" package provides many tools (ROS nodes) to configure, test and communicate Xbee devices. Four nodes are provided in the package: - * config + * xbee_config * xbee_mav * test_controller * test_buzz -The "test_controller" and the "test_buzz" are dummy nodes. They are used only for testing purposes. The "config" node is used to configure the Xbees. The "xbee_mav" is used to communicates between Xbee devices in different modes (e.g. SOLO and SWARM). +The "test_controller" and the "test_buzz" are dummy nodes. They are used only for testing purposes. The "xbee_config" node is used to configure the Xbees. The "xbee_mav" is used to communicates between Xbee devices in different modes (e.g. SOLO and SWARM). -##Prerequisites +## Prerequisites * Linux OS * ROS * Serial device drivers. For FTDI, the Virtual COM port (VCP) drivers are mandatory (http://www.ftdichip.com/Drivers/VCP.htm). - -##Configuration of Xbee devices -To configure an Xbee device, the "config" node is required. To build the "config" node: +## Configuration of Xbee devices - 1. Uncomment the following lines in "xbee_ros_node/CMakeLists.txt": +To configure an Xbee device, the "xbee_config" node is required. To build the "xbee_config" node: - add_executable(config src/main.cpp src/XbeeModule.cpp src/XMLConfigParser.cpp) - target_link_libraries(config ${catkin_LIBRARIES}) - - 2. Insert the correct path to the config file “Resources/Xbee_Config.xml” in “XMLConfigParser.cpp” (line 26): - - FILE_NAME = “/home/mistlab/catkin_ws/src/xbee_ros_node/Resources/Xbee_Config.xml” - - 3. Build the package: + 1. Build the package: $ cd ~/catkin_ws $ catkin_make - -To configure an Xbee device run the "config" node. By default, the VCP and the baud rate are respectively "/dev/ttyUSB0" and "9600". Before running the “config” node, please make sure: + +To configure an Xbee device run the "xbee_config" node. By default, the VCP and the baud rate are respectively "/dev/ttyUSB0" and "9600". Before running the “config” node, please make sure: 1. The Xbee device is plugged. 2. The serial adapter driver is installed. 3. You have full access to the correspondent serial port (e.g. ttyUSB0): - - $ cd ~/../../dev/ - $ sudo chmod 666 ttyUSB0 - -Now you can run the “config” node (after running roscore): + + $ sudo chmod 666 /dev/ttyUSB0 + +Now you can run the "xbee_config" node (after running roscore): $ cd ~/catkin_ws - $ rosrun xbee_ros_node config /dev/ttyUSB0 9600 - + $ rosrun xbee_ros_node xbee_config /dev/ttyUSB0 9600 + If this command generates an error: * Error: open: No such file or directory: @@ -54,24 +45,17 @@ If this command generates an error: 2. Make sure the appropriate driver is installed correctly. 3. Make sure the path to the VCP (e.g. /dev/ttyUSB0) is correct. 4. Install the newest Xbee firmware with “XCTU” and Write the default config. - + * Error: open: Permission denied: - + You do not have full access to the serial port. Please execute these commands: - - $ cd ~/../../dev/ - $ sudo chmod 666 ttyUSB0 - + + $ sudo chmod 666 /dev/ttyUSB0 + * Time Out: The Xbee Module is Not Responding: - - Baud rate mismatch. Please make sure the introduced baud rate (e.g. 9600) matches the baud rate used by the Xbee (by default is 9600). If the Xbee was previously configured with the “config” node the baud rate will be 230400. - - * Error: Config File Not Found: - - The path to the config file is incorrect. Change it in “XMLConfigParser.cpp” (line 26): - - FILE_NAME = “/home/mistlab/catkin_ws/src/xbee_ros_node/Resources/Xbee_Config.xml” - + + Baud rate mismatch. Please make sure the introduced baud rate (e.g. 9600) matches the baud rate used by the Xbee (by default is 9600). If the Xbee was previously configured with the “xbee_config” node the baud rate will be 230400. + The configuration will be loaded from "Resources/Xbee_Config.xml". Most of the existing values in the config file are optimized for Digi-Mesh. Some parameters are default values. However, all parameters can be edited. Please refer to **Table.1** before editing any parameter. More details can be found in “Xbee_Manual.pdf”. The commands table is in Chapter 3 (page 28). **Table.1:** Most relevant Xbee Parameters. @@ -104,14 +88,13 @@ The configuration will be loaded from "Resources/Xbee_Config.xml". Most of the e |FT | Flow Control Threshold | 13F | Since we are using the highest baud rate, we might need to increase the flow control threshold. Testing will tell us if the integrity of the data is fine.| |AP | API Enable | 1 | The XBee has to be set to API Mode to receive API frames. This allows recovering useful information in the headers of the frames such as source and destination address. We shouldn't ever need to escape API mode so we chose option [1]. Otherwise, the escape bytes would have to be escaped each time they occur. | |AO | API Options | 0 | Will need to change to [1] (Explicit Rx Indicator) if we wand to be able to read Cluster ID. Otherwise, not very useful. | - + ## Test two Xbee devices We consider the following setup (**Fig.1**). The block (Drone + Manifold) can be replaced by any Desktop/Laptop meeting the prerequisites. -**Fig.1:** Experimental Setup: -![][fig1] -[fig1]: https://github.com/MISTLab/XbeeMav/tree/master/Resources/Fig1.png "Fig.1" +**Fig.1:** Experimental Setup: +![fig1](Resources/Fig1.png) One of the drones will behave as a Master while the other one will act as a Slave. The Master drone will send commands to the Slave drone. Each drone is running a dummy flight controller node "test_controller". According to the drone type Master/Slave, the "test_controller" node will respectively send or receive and display a command. The commands in the Master drone will be introduced with the keyboard. When a command is received in the Slave drone, it will be printed on the screen. The following table (**Table.2**) depicts the keys of each command: @@ -128,9 +111,8 @@ Each drone is running a dummy flight controller node "test_controller". Accordin | 23 | Start Mission | -**Fig.2:** ROS nodes running on the drone: -![][fig2] -[fig2]: https://github.com/MISTLab/XbeeMav/tree/master/Resources/Fig2.png "Fig.2" +**Fig.2:** ROS nodes running on the drone: +![fig2](Resources/Fig2.png) The communication between both drones is performed with Xbees. The “xbee_mav” node (**Fig.2**) will handle all communications with other ROS nodes (test_controller(Flight Controller) or test_buzz (ROS Buzz)) and the connected Xbee device. Therefore, both Xbees must be configured for Digi-Mesh with the maximum baud rate (230400). We recognize two modes of communications: @@ -141,7 +123,7 @@ We recognize two modes of communications: All topics and services names of the “xbee_mav” node can be edited in the launch file "launch/xbeemav.launch". For other nodes (test_controller and test_buzz), topics and services names are hardcoded. Thus, they need to be modified in the source code. -####SOLO mode +#### SOLO mode The "test_controller" node is needed: 1. Uncomment the following lines in "CMakeLists.txt": @@ -152,13 +134,13 @@ The "test_controller" node is needed: $ catkin_make 3. Run the "test controller" node in Matser/Slave (after running roscore): $ cd ~/catkin_ws - $ rosrun xbee_ros_node test_controller master + $ rosrun xbee_ros_node test_controller master 4. Run the "xbee_mav" node in SOLO mode. The drone type (Master/Slave) and the communication mode (SOLO/SWARM) need to be specified for the "xbee_mav". You can change these parameters in the launch file “launch/xbeemav.launch”: $ cd ~/catkin_ws $ roslaunch xbee_ros_node xbeemav.launch 5. Introduce some commands to the "test_controller". If the network was configured correctly, commands sent from one side should be received and displayed in the opposite side. -####SWARM mode +#### SWARM mode The "test_buzz" node is required: 1. Uncomment the following lines in "CMakeLists.txt": @@ -176,7 +158,7 @@ The "test_buzz" node is required: Random payloads (Mavlink messages) will be created in the Master drone and transferred through the Xbees to the Slave drone for display. Payloads are arrays with random sizes of random 64 bits integers. -## Communicate drones in a Swarm +## Communicate drones in a Swarm We consider the same setup in the testing phase (**Fig.1**). The "test_controller" and the "test_buzz" dummy nodes need to be replaced with real ones (“fligh_controller” and “ros_buzz”). You can download the real nodes by clicking on the correspondent link: @@ -184,14 +166,21 @@ You can download the real nodes by clicking on the correspondent link: * ros_buzz : (https://github.com/MISTLab/ROSBuzz.git) To run drones in SWARM mode you need to: - 1. Comment the following lines in “xbee_ros_node/CMakeLists.txt”: - - add_executable(config src/main.cpp src/XbeeModule.cpp src/XMLConfigParser.cpp) - target_link_libraries(config ${catkin_LIBRARIES}) - add_executable(test_controller src/TestController.cpp) - target_link_libraries(test_controller ${catkin_LIBRARIES}) - add_executable(test_buzz src/TestBuzz.cpp) - target_link_libraries(test_buzz ${catkin_LIBRARIES}) - - 2. Build the three packages. - 3. Run the launch file (this will run the flight_controller, ros_buzz and xbee_mav). The "xbee_mav" should run in SWARM mode. The drone type (Master/Slave) is not needed. + 1. Build the three packages. + 2. Run a launch file that will start the flight_controller, ros_buzz and xbee_mav. The "xbee_mav" should run in SWARM mode. The drone type (Master/Slave) is not needed. + +## ROS services +The node xbee_mav provides a ROS service xbee_status that will return information +about the xbee module. The information returned depends on the argument passed to +the service (example: rosservice call /xbee_status "param_id: 'ARGUMENT'"). The different arguments that can be passed are described below: +* id : Returns the xbee module short identifier. +* deque_full : returns 1 if the out messages queue is full and 0 otherwise +* rssi : Returns the average Received Signal Strength Indicator (RSSI). This RSSI value could be inaccurate since the average is obtained by getting the RSSI of the last message at a fixed frequency without any information about the sender. +* trig_rssi_api_avg : Triggers a link testing procedure to obtain the RSSI with all the known nodes in the network. Returns false if there is no other node connected to the network. +* trig_rssi_api_ID (where ID should be replaced by a number): Triggers a link testing procedure to obtain the RSSI with the corresponding ID. Returns false if the node is not present on the network. +* get_rssi_api_avg : Returns the average of the average RSSI results of the link testing procedures. +* get_rssi_api_ID (where ID should be replaced by a number): Returns the average RSSI result of the link testing procedure. +* pl_raw_avg : Returns the average of the raw packet loss value among the connected nodes. Returns false if there is no other node connected to the network. +* pl_raw_ID (where ID should be replaced by a number): Returns the raw packet loss value between this node and the node ID. Returns false if the node is not present on the network. +* pl_filter_avg : same thing as pl_raw_avg but for the filtered value. +* pl_filter_ID (where ID should be replaced by a number): same thing as pl_raw_ID but for the filtered value. diff --git a/Resources/XBee_Config.xml b/Resources/XBee_Config.xml index 17284b1..e33fdc8 100644 --- a/Resources/XBee_Config.xml +++ b/Resources/XBee_Config.xml @@ -5,11 +5,11 @@ 00FFFFFFFFFFF7FFFF 1 5FFF - 3 + 0 4 A 0 - 0 + 1 7 1 3 @@ -63,6 +63,5 @@ 2B 60 3E8 - B0000 diff --git a/Resources/XbeeModule_DataSheet.pdf b/Resources/XbeeModule_DataSheet.pdf new file mode 100644 index 0000000000000000000000000000000000000000..41db1d3aed7f2d4553f4bebf4f9066206f04e02d GIT binary patch literal 1014096 zcma%i2|SeF_kW8@gb3M}EGc4U%#0aAc189z`%d;f3PtvQxKQD0_8>$v5kFe>m(w8!r^>O5GGs0 z+eBBd^2l1)m>4)%xSJR=L3w1Epb#h=f=2SlGeO}9IFAGqk{1C-^T;uw;XEo#XcPj% z3+It$(qclu5lAK|6waq3Bt&FlV~i2UwEsm!aL2*KbYBw;fg&P+?0-R#OxRCMHvhCC zkq}-`8y_055c755ITQ@s7sZDHJ%{E+fZI@@zI+fENCzL358MVrg6!ktg~M@m@WKB> z9s&vhJ%>PpD}JAW*nCpb#Vy7Y7u=hlx5^%m3j%6fhZgJfOfd1>-=Y zK{x<`ARJIA5`+T^gM)BDd0`+NP&gEX0}4lja6l2D7y+n7f^Y!T0^xvyV;B^QhJbOP z(I6Z!2pgVqHoF9Hd|!HYzIaPabh))^=- z3JS)7hJbOPQ6L;}2oi(?pdbhb5OzU0;Jl!96$>Efb)U5 z3P(Y~@=&1l4L||54*>;_5du(*JFk#X(E0{N@`7SJ3=IYK1>6FPv2b1(i05!#UQkSg z^McoII4=@p3!Ik^v^K(dQJ^&x4hQ=H4hI4P4qiB%7qoW6fpNnfOE??>iuZ6h5|lRq zT|qp817RE_4*>)_Tw4&lpt%bqg`oHXM<7744i1D3+<6K|fMXpT2?5PNI1&cp797dT zi_0U-G{v2}aO8jZ1z3JTwjhBd1Q##zKm5W6q`0`x@$rJzWH^xjf&9mZ0Q-uM545hr z`B0!-3eJZH<3&NhwxFP394HvrFDP*Q1H1>;i~5f_j^aate2+qd)iM(7plzkI`U-6nIVo@fllZ%ox{BaKf_=)z2U_>pwIS9AAL=44QvHdJpc425}1sfr8FFfYTw+ zcpxEQUjd^Anrpz+1;tJzu;;|J1qp1Paq}<$83-GYih}m>NFZk8&PgONjxS zI0TMFNs5TT0oNema8Ypyq==9XkAj1V3-*8$1_e$u2^^ga9Gv!!F(E_*Y-|$pl0*c+ z`6h6x$%i>@`se&qf(Zr~#v^HA_a&3<~2F5^{8MFfp(uA}}8sjMkB*QzdU`YxacX>J`kF>O2@L zym*j9mo*KP^&tWz^%kFO6Euq-ZO)|E z*7|mrb~Z?5=ghF0BAn;d(taAci9NHr)YIte7kabhB3+a^dqQW}K+#0GmIXuU=&Y^# zo5ci|!WhH)JSWRv38?q3Tu~LXn}bc%Le!Zz&L_^ru6XJ@oznbNyh%H!j zB=6!rkSwcbt1C5NomU_$=2Fk2EMuu)%g67lJQ8NkxQ6cWi$aK2_{G+u?@mHx_H6kI$-QYvuOm{nW6Y`Ou?%zd|N({oM&f`MuMwjC^|Rzi+;KdBjpk zjhn1pQi-T?tbBj?#PRrRpOoC&DGKWG@uzO^MrsIn z-)0ea2`{%P(y3f4rH#*~zeRidwZ)4<<;#5zhVxH)b?B^0f9WybX4};XEydTGc~WQ+ z8QebFSUGx`uOj{K8M#-=zf$#H=2uSa{^S-PaH8c(qHyZaG1pccMh;Z_wKnKKCZ&EQ z&Jmr-L?8@#!ru{7C@qn@B~0T|?J8TJ8^cr7+*R}QV-_LzC*#K&5yKa^k8)Z&W~)z5 zewE9s-lgoSCPo>Sy-C(*^HDfL?1N|HSmrDrZ+`#x$bAR=AA?8rU*yl3E*gDPyKhO1 zw|JDUGLS*+qQ*i|N;-)L`s=GB5bYDQO`78(l14m1!Y65Gm4zzX*MG|&J$WRnVWWnK z0Jv7!j}7}5Ec-F=pQ{@K8#4|Qn@c=5O`Hsj4V(-xQ4t8(Kva}7ur_hTT;Txm7Wh@( z&csH<$jQRiMhkPTgKd+vaMIzCcXqM@E`WeXfy5EptYBbfB5Po1Vuk6BITi-GW7=+F zLYk_h$v-`?jo4@Q#HpAALChG_fXV5BPAYD8COl$*RaUlU|GOgE|1$;w#uVUqi%Ci6 zpZlZzhJARF82k5(x(+M{Di%&wCLBAvM?@|O0bd9DU@-3Y5jSyka%4haj?n=VZWy>2 zC>uFg*kM)=%n=@w(jOf$E&Cm@4%6b0bO0Q8)4ouZ9F7IgBj#XhCu(~~3-cS0VKDKbVLHHw8e15E zS``c&fWDY<*>j7MiKDHvgAsQ4_7_JbTPI)zVuI|sA2V=&ScU2L4`Pf@_SR4Z%*Q>K zDQQ80eFi3v0G3hUk`Ju|T>Alk-Lq8<^ASj0ar}sp@;|A-)(7(h4kg4r3)~USf8ne^|N48H~t74iEORKY;(q9pEGZYa2%7p1pq^aS$CbdHf$% z?%9SBxyRzaiUhF-v+emq!lk^e-Zzla2}2Xp3f5cr-_jFtby+rLDjz3F=pIJV`0l~@&6;QMR$--ZWsMu-C( zhduk8!B}}X_F&2Ya75y;XHO{xIOd4$5bVM1ig85ZuxC#xR^;K>gDH~05sAZ|J*8NY zhhq=s90o@u4tw^LVnrT~J$o_mj}gaV&z@3@NMJf1%9mJ|{~;2GJ^O(dBl2)oqCo7y zwj7+7d*cj<#2kbiV#G0LJb(HU+j2nUo>B~O%pKQZL}I7!LExARvx9`(Q;HRNxDm&k zO5j+D!yc>(3?X?j)eeWT62uZ4^ zc{ui9$|U}@65Dc61;lY;n{Q-Qh z<$qT0slbL{%r*aEMB=gsxctMha&I;QR$?k24x@n#)v%B+JnH{x8MN( zbM4tvfd#&QK=jw)!DSD&Q1rkg+E_K4D zl!GJwFMBYTG>5Sgmpwpz0FIUavIlc_cnFc0lHxyy2itPc$~{2?y@qxu0qNRV0W#m}1C3to(;Pu*0QU*xPR$D{Gx{jJ~MtlZlk9h~aemV>_h zhdr>v9X(;|bN;jvbL)H%`2L;@@a5r-o)DO_Ssal#?7^zQ0zcf*6SmR|MDOTj+qWa#p z{ST2i?Ac#&FjgKCIEX!%67@eO(ZB4$6yF?Tq1anU|F9B=Jy;dkNp#3;15*P0=kQ=# z4zOo`^#*`r$_@@;C8in!M}Qo2k$W!qtCiS^{KxR%uxC#x;7jP(;;>w3rT$hP>fz6C+HQ>(&@Sd-u(M+~n^G-^U^<1>+GnF*R_ua^jI!U@|qZ zax?)x+yvfIRTkO*Rrw|pgc}0eyX*efRvuL`rT_J{wcC66;OxV$$@_Z#qi}1#R13)e z4%TKpeAFUW13CL}af{rMOWM9C>|0;&Wd-|;XLa}s)@0uJ6t6GqCWm%1+B8PEzDV3K zwGIvYSyv$G`s{PcirfhjYwvu9=So(&wiz#MKTkn#Bot4&xsa9*jRjMwLV^fU){m|y zv%}6V8|$N=OvV*bb9hm~XXsylPw;+gHl>h~!CJ4uHa;Bl{gnpw6RY#;GMOVsRP+5a zv!}|g&+3p-J~5YAmUas{Nt4HB)LE(&QS`P675&jJg`!^mX*;ZrD?EsnhBkOztl+6w zLBm*|ZG8N?h_4L%63gqZ1%k~o%4BMG=+MN?CxWjTNn@afRIzH`s%qm*orhOHP5cO3 z6^t&MU*cu^DzQnSf21bG82(?yDSOl4pYbzrG{MXf9?_dJBGM9^m=Y9a0~<#k2^*j~ z&ceowN8Q3k#KzI$-`^!I92}j*%nclX4Lf#v0mU5H;tg8|%zW94v9bpH&j1mUN7>oX z2~%aF;^1t8EjPjbht;ZXVeDk?sI`}OV#*GYSTbT>w7|T`1OxJC7_bsxzA>VKl3}1G z4*_TfegYXaFQ)hbXgka|=6THb!Dk^%C}8OV-dO?kqJW=JCO#lDLIB5jnB5#7kaz+0 z$Usp98t4gBG5}jb%w`Ak>HzT02ot7+7747T*q^`_2SW@5P>q7=hXBqQ(Lj2Mc?}T( zWYq{vxdtE`WAWbE$==l@Mi)?=3S6M?{X_tPl^3|X1B%eG`Y^A(V!nX_e(X;);1!G= zKyfX$AGR-W{s9N{@B+_aZ3O(t2V6B_GJnh=5Ku=61h~Wh!@Pcr`Q`-(i2Vj^!yL?E zUT8gp7!)>*+k5ih=Rf-b^|%L1cJ?OD{-hLfG{P3pK#(Y)G|5id#KO!RsHXwc1F>fB zZ&zSwVD?!Vm^uD44Mj0^I9D*`I#)0?_`rK>aG(nurGuTMk_OfmR&E@a>CJ?h-p%gOg^`GjnH8q0 zN7>25T8#+><%S@6_re}V!vBcEqj3P!A0h9+g8Tmud6)uc^nR%-KoH>7r$0hq0zaWf zq-y`-MyqSQLCn^Pgh$jur^Hz!Nl)`Y9i9ZUUw9WnLFgyB5JwXiRh2byE2y{&UicRF zG-Qyb`K;D*TT{~&$FBktg2T;B3Om2sgue+ay0&h#q8ERAw23es zIZGJ)Ky>5bb?Vq~y{g~%zqaY0|B8-vF0l33`f>UG63H>U-O};a5{Az8cZo-g$-@?7 zgtmHOtFkN$^tY0ad>+#By1TZLy5;xv=vh5N$hs|2=gf>(`EsY}{p)2vevcCMk#0r5 zA-(25TYcXz)^TxDy(i;bpUo+V&F}eatr?;9Df0{0NZ;_>Owx4iwPH^0{I)&5UOD-z zG`900VmI>`hZo-ThQqJy`VwhA&!*kr(6&mW{<&?B_(zrRZlqm56=};ta{owvuIdjX zc|)qsZ;-@$oQ~Qd97+!+Q9H@+JF>J2?p=+f=w1_&HX44`Z~ZIP$CV>Ijz_ZE8YX--L{b|Wt?+A-ok()PJ9$?$ ztq3CS!62iUsFcw~kxuf9ydFWGM#8NUbXzQmUml+{Ih*{vrOpkVM&;SlY%H0x9XhlG zBk`SE<<$69)Ki{MVgyt5$p=K29)?kJB)Py$3=u*(+zQ@F?Y;fWcjjZ|dua0dez@EF zNm8WtC{tZ7EqMMam(qguHFWbHn^&BW2juOH(GTd!WYObMUtSxJtcu?qIY}92K7K9C zWZ*)&uk-5jpMl-JCv0-~VuaqY8mkbzWp3<^J`=dXd|m6aBP|QPn)|I&Rb6j0zn)RH z>^!r2!{h7CZsuG5j`8LO%ALQNWo~h(Uc!Gdw5&P;~45vOoVkJ3cOmTwYPxT3P3A@7SxL zhHQ8t&6%48go=X-x}h>}T`O`w(_g+taVFN1wlP5e;c7}y{v+$L&~D~d_3suLH4NKN zv+m?L-o5g5F;dT(N`Z@mE;6_GQ*Ca(;1T6K(py*a_y>QzS6O4gH%>btrhSFh?Gpc3 zh9OIED$CbSONuV*FKII`&n|MlQYTOxCFArMFc2tWU(j#HgF*9_f6X?crw0`cZVfyFaq=?IS_q zhopQk&Pc_Kji~h8S4B*+$FyW(H7Xdlb#|@jC+vkM{SD4?>GKFIcQi#1#%Io^`;%FI zU7d366zsOK(@u(M@rTEOFM~mndIp+#O zl;(+fd`?nDc;u(YId(Etn%5J{lL~RTrT*Y!-7v=ECD5KV@r&ncQocEO)`RvV{tI`4 zbPDkyqj}w6g64#u!Kqn+*@3g)&zDt**sebjim5S>H#SOO=6y~nI#f+^)JP1T$Gi`&={R}LG=rn%tMa?& zdAG{SGzZPzvGUJZL`3CZziDO9me0gA&c>|IPWP^LtjF-EqxlJ=oQ4qY*JvkYOQ!b; zB?fp};+J08DzU4Ee;%s8li%(^GVqDOBrO}p;{ow2Dp&L6O75d!`gHN;t0CKZuA=gM zcM_?0+x_MGvq$K%h8C;Sp07G&KXuOc^GEdEpy+#4xb}7H_>tg3Mcvu<{^Gai+Bd(O zGd|GjFR@ETmn-HMDIP)5jn=R{m>RhH>*Hu;-L2$b7AM&A@9W|>9@TmOzRqDm?L+A= z{We04nkoFNW=wgtUxNxRzg=+2f2Vrh&VN`V#1`)ZId@KJzH@iv%;cH-op1F9Il?{K zwZ~`_zQm{z2(C6O>~QwAtI!&^o|ID|+F@Z%(GI_@^hQclTueGg_7h7uQqmq_bdi8mFNO`n)aPCZaU!8$`J(gLp(APC@+X{7kfoRG300%-$Q* zSuzP<<1RjW8O>ug(dt9L^^%3|T831Hh_sl7AB5+#&9#{46^p)u(szYwoG9PDcy3pG zzn<0jJ!$n3Lf^F!{NaF+x?ci)LPS#UCiOik_$~-Z*)jV^)M_@k%@6l2#nCcw^AW*-b|_ z+iSEEj2&~48>jm(FN$6Bs&-8Z7}3Y`-+FqX^*&x}cX#zl zTtcr)I%kl`8*k=ve*9H@(ec`6)eI3~eGP_3H@|S@AHCNXZ6Dg%XKG*DGUvZR@AZ6E z$KIf~%*nCWY%JnU+e4E+$>u`m#K3xfAqs=z^(RefrO$N=4#ZEZbPfwpRb8+r9#_oX zAS)0Eaor~1Fo79v2P!|746!#PY9?QPmat(`+dwm|7?V<$gY2tI79VI3dN3`-u(B-| zQ&T^Exb<`AE zrz&Io#Fg~+)d=NJ;4vB`EqLExMPY5lKarA$pM;(Rmc?LX%T>aw0jkCXZ;I1fqA1eAcB#lzQ!h zASHntRhw$_=rU=tI746MRKd#Ii8kJKH|buNcL7TatRF6Zrk0M1Lu{Gs)L01}cQ)vC z*tTe)x21o{B6bNv2($^&ApE))wKK`nrhn~e^X=l18uc?A3korGmx^e+z1J^vKfxM5T{pa z`G6!>sFL=jl)Y0UX@CQ|2_ZX;$bG@8b)_DssWfY-8&p0qz1NqB@$zeR!D;~~=POtZt){%xXn zNz5tXW(q>n8K+icqV*oWzD11GE9@cowxUP1E3xgBQEels?OwPfeWj4eyIALSPvA&t zR+!Z9t@C!n{cJQOo~PF`t=$c~DBh2^LBpCw$`K&~G-nqUjuIJPJR=cccCFKZs)sCe z(DhMRo}j8g&g;7EAH0)%A&ApsdRc_mt+R@U1%Bf(2C>K384Ni&10yb@Am+$?xQO`G%)#7sEK0 zFGf>rkUjB_&APX9RCTH7jdQRu^C961x4(p7s2xM~As+jzW&y;<6nw`7Dskt^*R)<~gJH863uu6-!#1F1}$IGc3 z4KI>P3%ETibWpl=OS7y?Rgv;@)G*bBPhyqV=lCG@H>9;0yfZKHsTGsuv%j-iz1=9o zL1-eEN$f`EZSvgx9^~R%erBG&zL;pWPL!)I%~tbG%Y^uzP)kCqjX-0a-U0o-Ciw?Z_d~$~{p&|t7_`Gqh z_8ON$V0wA>Idq^><0@mzTaD{-VRg3E&iJYs=O270F252bBV#R1(a+!JXnHb)OjzmX z@i*gs;(cTp5$AI3f4C&p>9=d%tf$hoE%=gn`Zt@d(-K~%VFFWti{j#o-`a3F#>u6o za^@a8u^%*K@%W~}8-DubH8AFA+1y7OGT9P#Uov#>pYeJ#9QWkOWBcV6$|~WOW1e1o zJ<`t1Jsd@)4)FFQ7;jCC{irk3c_dMOInDa3lf>RPH+328v!poHRWchmqn~Cyl{S2^ zNpU?(LsP_0ZAkt4_pr9>l1c6f+^ViTikywSXQCf9Nf_twhgDy2=6fX`Z2dltPv_1# zr;#H(X*CKQXU@DwrMnWBvtOF-f3V4H3hk6PI@f8qBw(C@V&xt>&+~GiTMn>El|MjFnjQ{j3eG-DJ#8z0b(f9Lp0av-pY+ge@M>75S z-sr92TX4V5=Hki8=3=w8akFcQ4xR12nwd$zX#LFMYVT*!%h&7PM7Omj2)NAzJJK@> z|L%I?b#Ifz>&|9Ztm7_fwNAau@m1vS$3Y(w-V}Tg_@EddLR_G4s2|W02)#xf>0*7W z)KE4|-fqUvY>S9Zq^cz{!iMgGar?S4zxkt!H8UMiCk3y5eae?ZWQt1S^@uOJ+gWU#Hi>izt3QgvGffI? zXtr}py~c+!JC5smxHJ%cDt_$$=9BCEWet(fLc?B@uJJmm#l8tknk16zW(A#iY_dT zG=4KSx+=h+u{P4wfV3L-BcpfQiWR#(;X2tp%2V{Hw=Xl*URBIVRX2RryCW@KV}9*c zR1Eq$wM`36{fqTPwbma$HXGE0-Yq%8#6_sO17DH6M{(ko>rwNH7gmuEFcn zb9iE0QO2*X;@$)lhIC`6Y ziPJHbny0+!ygZdaYV^}#dxQ5UA>ncZ`8e!!E^SpfqAY*@TW)?@WPzk=U~>weBcp4Q zm1%TZ3G=DWveuu|apy}FZo6DP7RXfJFimG7k|=)DM1+R%SHat%U(ZxuO0(X`E*X_6$zkD1b+jjg4+lgLV%C_Q$+F8_?BoblbkuUQ&?Cc!C@qT7S<0>%xw zu2~;HtCp`0m4sQk4vT!Yt8;H=7Ya#QdPHegNBZ$3l4W$Oq-8VzndSxiZ{Aj;99nPi zwRCMMOOgns&Rk;Sx*bA9%(FP#$R;CNkfXI+Mw^_Gv$I@MTy^ie$12;x_N{!Uwuw{h zEn3jq9};vH=QLj>?FMg_Hp3Nt9GqEBTzbSvHF7eZ^{6v@UC?pmSD&UGqEF~>SG4t3 zaZNp0iOzqv6BNmOky}hmkb{LPlTMD+e~q0j-58zd8D2N1nqTUJjQBM5VzNl^>}|!} z=bplA?V(jW&!V{$EEzO*S7>QH)dye&4o&K7m9Eh_nuY0AbAx3&>ld3w=BdT5U+&29 zn5rBe5S+k;UT$t~X z?<%1BxMPm51|PoA_amj1JfwI#B%EQsd9+`Y@ztl*pN~XtBQL3orQM?!?09^mQlqRG zS-dPq$*kyk+Wg#aeQ~A^@o)3_UnMpy2k(FQkoutJ0l!l~%5yG`9dRf1+USo0bI({U z$ix(5E3PXAg}(SPs=aBEqAZ^&JfyYq)Z)2%7e$q)lLK;1WKu|vMQ43uHeJQ}gVFTP zgf%NKbNoPs#1(t!$7Zoim_n8u)sYiNUnH~D2m9aY5Pjm|M`iS3T|cD5Jl#cIvz! zUAMK!&Ep%lTZ&d^Us@4F+m1{;GW*zBRJb(LFk@NPRk+kR2E-==DL1_5#uaDg3m+MGPydwG`+T>}Nfoyf$ zL;3D^^4^vP_n5j(ZWNKcJk3u}amD3H3{?DWn!A#qNp+XXajMNw5}Gj)YDT>2^!mh3 zJ}v*{JYKS|`F`X!VAQ4cgdOYoF4y7EHg%nGoJ+ub+_8 z9lFCvooCmQ82%=)O770GZ(`L~Wu?{h6V{CMf_84*L~U)JD|Me*T)!62B$fKtpJaGh zJf!N?xwtHe_zJfc>YP9GJ*@7``E`9+rjORwKhG+fXAF=Vd39xfHUB>M3#Ib9_WCy; zZQFu^iL_NEE)gxUf|_=71j;+i4(aI>h0M zvR}} z4a(H_J$e{TPRlvvpNq*1tlx6 zo|Vms;QGu-{v|+C={UmqUNGx;1Vvgv^FW4sdZsd!gsUq>;QR;OY-h*3XnCbK^fq*t zzI;9M%H><3sJ`r=bMI2BiOd<#PBLB#hyJKN=ejztaHcgqA=aQ`WH_A5?N|o8r;<=06+#(|SYbInp z0q6%i2~bJ)W1SS^Y(rKs2exXeYV+D-C+~0ybeLb72uk^o4&@P0Bok(yO1U8S+IrS% zpe+8A)~E5z&RgX{yv}^+H>UWfxGC&-8%IA9TGDnue)oygY1W5|Fm!5`f#Wpmz&c*V zC842=Nj4T!jW6V8L7YT!vXYScrzbEHWb=+)^nQlKQ>gUDfH0Ub_{lparxyWD;|8`4E#<{R-WDx6eNw`k}DQJfUn4BfWkDoFwH z53|xVWB#97t7ig#w?(V-C9CMEFnR@j_gt@A7&EQT*(r9H{4MSwc-M$nQ_f~9Ql&`! zP1S=h+&5%1Bm)gjG+zjL+7nW z(LpwiPxvQ&Ua*>voKU~6kgHP>y>zQq*S$+S&W+Cj5q3{tZQI2;r__}3mC*0;tgvcBwbIm!I&dX7Xg|WiV#ia(*9&EQ+SEn|Lwl`r9i` zxE+0{;Ug>KozFET5u}>zl6T*;uZFNJwgJ`_UggQ0_d?9t;<+~A`5CT;&RO>bm&j}C zuS)~q=9A42uUUm~(ca`I;85aXg?px+qN8bzttqfWmzif!3%P7xDK08c<95g?7)G2T zxzc?qTx!l+I8`wuFHw=x4(cumy+~M^)HSj4nd~uK6l(m#Y-noxwu}tnTKnVHiowzG z#2ltPi^02zpWOSr?-xdpJ|PZw=2WYaezQtYLQ^4&r`zzD()7ktp#hpC&Q^n6AIfW>5r&+$ql3$D&of^p51BpHvI11|{#)J^3hb zJ6KVT$lGnUj29M$3<65OLI-b(v4{v^MRP7vFSyb#D_{ zGA*^L@=KM?@s>_hy3K_bgFH=>R80-{DGcr3pO?WmYu8Mps?hyxU*7p5SfZDUsJ`AI zGG&J&bQG>tay!41qxXBAK=ZNBi@`xeEKHhGcBfWtjaNyX%iQOhhjiqt?s#X--;*`J zyA`t;KAl+bu7B0C_l;Hv@>8Y_vC+39>=ipmF70nt#};LfE9r6<>!mKrJ6Fh_c5r75 zajQEgIAkD_7(w^ON8?`CW$UY!0&a4@d)*3+x+7g_Z@Gl)mhHSY>;C37@N{*%bIrEW z=1UOIj&wBrCdA9^=LlQqx0%a+QRPeP%C?chD4T`X-)7i}U!&fSg;I?3ofyAZeg8g1 zz%`C2XAOIO*^yMu=Uc|-i32sn-Akgb%qUc9&|hX1N;C03-)=T$PfxghjFPuQMm%5h z3T)iS{yBd5PSS#59&dd62Llv0!P1OgcksI4m!I{YwuaC4^V_^j^Sp7DekC?6#UqEo zCVhT%_i;m2%GZn)!dm?gA=Uk{>5-%};o2`o#yme{Uc9Pkvh3%PIJ_{kZNqbk@iAOq zeBCAEo8QHvg*$ZWH8iR;{#kVeTd{X4%93l$$(`&e1=&jNq?e>@S_++^ajXU2A+K$W zvZRoC8@@GVUEy>!0geHi)7;M0L!Dv?3tSf#*ov5SwR+Cqofa_CE!g$c@@M3$+8XKc zX!~3yKqs~+qF1#dMAlivx6gKsHuAWl;Q@5egt@pll5An$4?|6i~H$puV zUr;SrDfRi>I;<;HTq8Ly$NPIREcop%%ySt?C~a$;IgG_u1GUVGPhV8u_3u{Ip`S4*EzHs=BQ=@i zzk1yyH-U~F^+~4KMfSx&ca03xrrRm;h1ABS=AZgj@1L?ZtSmAz+D2Vcn+8LyDyz1MPi4!J~<@s}c%gcn{TKsg*cUyww%d%9zo#Cx)^%qP`b1#^* zR;Cj$J7n4!2Gr501k2p{F!C~4ndjWswR1)3TLp_PDr;Al`hrf`6rW>+o~5Nu_aaY8ax;_aPsHUHBeFPzNme16Bt^fo7f(qwnt zxk?j-+9{8>pOPcIe+Rw%Wbl~vTJa2x@a{<(486IdzKVc%Z$z`k5D0t8eVf41>J6&j+OF zoQuqR`pjKzVJGQA0Y9CtnTGa-n`CS}Gu9nd-JRm=TLY5Wos?Xjdxd z6jbE8sA4;NEXVT6dDCAvsOuk^wsd$OSG%hDMbp$4u47o=|0c=8b5&JoEz8ZK@B~6R zAh>eqv6vnYEh6q}2A7O>A3XZ^Jhw#QvX~;whl#fS{rrR3&as?jYBDK8G3#1(JD-R* z*H`Lhmw)C!O=9zdyni<4iFia@ZDfr%o_r=U*f+w|`F=33`hn?Wp^=ZAtGLtG%V9=O zFQd^G>aPUoIxIhsw;X+I$>jnKixn2wXyT!%iK?>97e1CR*#o&Z=3luXJg0T{4tY0) z@LKEKLbFhQK|xNr^hr?~={vrxtfM9RWGVN>ADD}t6(zG{W_@J!3{QcXLS_5yF-g38 z_hXKUz9;99BtPMXS9d?s|Aw%zaCW$-bm1*)LV=aRFQ-mZx3FPX-;c7Yd5AHQztYAaS==+}J&eTPCDD37-u50g<)$u~Duv|;0W z=d$3-$oSr^{{fQe)c9cCBh`nR*PN%xbQT)%6{9!GFKEJ!1<1X;TH|S8-pzZ{gb+XX z%G=xpL_?j>o0_&66+wlykLu9O31vb?*g*_pPe>B9{3r;&Q!e+H;soAw#WmUO*cJ9Kp9Iz3R$ag}4O zNWiwLKV>H1)|>>_Qmcth-|YaG|T-&4!V zwbJDFdE|{793^cc&W|!@IDPuLi2s8S`I4uyf*BK!!Uwt}f{`}l<};6AF!}j;J-OAW z8FJ54=r~h}VvyK9(C27-AnI_35?OdG+hZzPphnAmc+ilbM=M zYp>O6Jng(BwG_?K^>#@y;%iW2-K**k2Gu^~+ISYd3`4GG1F|AUO&y-U6Z`yJK0(lR zKJ(?5j_@HUcRN5YE49RC1;~IZ*n$$+je;)^hDij-|;OWeX?_r zYI8Zql>{G;=#R~u)sZXUxXzIsVfQjmKkW7VEYIF{zleqNJYwiY#eM z_%ow)!+6<I3{L4Yv5#|(zOusVY7+olW9-hyBIo)xsj34qq)B5F%0M%{Nw3eHn z2EEN>x~25I?%FG}=oE|xuFldMEhZ^t5O<{WQJ&98?_P}Qm}o7oj9;%CZ3}1EidiDK z8~1AI@`$Rmj<&XwQzZEdr_eBat+Lv>5-yjrqlhZw2jv$&g*KbMxB12Rh#DEOkb9!# z%!1(5bmGk{=UHTq#@1YluO% zFrZbF*2?bF*cV-JCSKu2O`T} zN+sK$yL!&wR6c{Q(8+oyKS9864XA&F{w(fmSm!)H#je9}gJ^)(4kiAC!|`6)fceuo zmf#ClBf9UOGr^ZrS;>=Yy{+$=VAb1Jf5zD~?upwn@%gB`U+Jm8-Beo>Ueg{ThpBw^ z(o3xS@vKg={&NGN!)^-qFCLEgYPA(fZJjUuITf9PinTV7_)wSBPLm=H)@p-pwZc#2 zKVzsXug{iql8GjAoMq1WA}RST#q;@ehcwjs>0+aS&~S3-$tm(x?f!zFZ$9wJw;M5Y zN#vPOw&=4;7D!wq%bG|?_x)j}PQ>t%=+S&esGdstTWyYjv$D>Mg&E4ZpG%U*jUPeZ z4!;mQnw=v5zTdE;A5|N}ZEvIg@Pr~SkN78Z8$2^9^0;V9$rL&PI%uxgF-=pLFO`a= z!x7}iHS2=e*7?-Hp8kxqMgs zcEIHjs=cYC(~9h)E~# zXKDYnr2Z@htZ!edH@qZ~MwZ6Kz8#OxbE$?cEK?Sm4b6s!RI>0+Mh*Bg`6OQzM9)i={)qV5 ze`}y-qPR!oNP$B^ZryHeHcPOR+Jz7(Kk$~knQu8@iOU2vF^4$*pR{>6vLH+WO^`@HZ@ zx(7)My@uOHEX()G)Vcl~8`RJn8`Ow3dqpww$@lq|nOORknd$j^qRVkNY2A68YCZ4% zswMH6eEI6`TiA?W>Z$IR-{#ZS+mWl^i%dT|O65`!Zj*#+;fLLexOn9w(bVZ57s7@v z#F-Qe@qXgEeuVTFzGkl0_?_5ew@+OjFxhf0dGvLyzfmZZnORSLvYmGBbVAYdFT>8f ze(g`9PQ37aV)`ihv=O(>ZM~wPskk29&F?R{p6}93QX{q>d!MksO&^;n)OJN9g`u2U znImL`Zsq1z1M6W_2TS}aY>F91P^UG=bsBZ6p_S&D zr@v=vw<_4!hNju>t=0>_edA@(yFj$MUaZd@%vKVAuMu&|DEI!)QcI)Ug^3&9P>q;Q zyP5<)g;tIQ>xk5O-^Q{)VtN4~^7jq->_qwocl^W)EN}OClLihByfHLP%Gts1jqD;7 z>7vg4{=7XY!9|zbEaHrdv~F_xluKFPGzz$<*jUksUg&DN#oTW+5h(GUjTS!vO=p)i z9mlG2Ohd6(UsyU7k>x2e$P~QW+|7{4Ec$x$y2U#)ddsI8^C`Yl?XQZaSbJ*TijDUB zc+Alddk{KDvrCA}eY{03_`#uY;7#BR$?7<(M}%p3!vfcEa<=N^1AC~E9ufMbuwEb*+wCAG`ZYBB@XCkN~X$Ofp<5|#2p%w9%|){M4Z z)k6zs>8AOf(K9;`mlJmnrD!0 z>wA}Kh{U&R@}YCbALwm2>fVX*o zhL8>y z^gny?UJK$rhfq3KsC1(wSyA5&cJ;&o4kz`p;ilsUw-s9v`eg%^qC}HXwqn9)SH)y^1ccYe%j@9EO zrG+)Ktfu{J@{~;8p_n#&RJp?_zC7V*RG;KK(?T39JYd~M{L)Q!@>Hk0?C?2RT7`(0 zdEGU^>uSgEdRrW`XGO=nJS+0k$AY-({K?L%FFmT?GIVl!TO8l)5pXE)tPryGkSI~o zo#9k%$~0@sS(2+7PPbCqT$7parL}!k5&5{gyOWbMav;;vRJ}KHv%Fi?Lo$RKaaEYl zWNt1f)Bc5OA)lv-ye}KM?Q5mX_1iZ-ahgW;G^=E$`_6E`zN~H<)vEqdjRQf^Sy5OS zL^BszeB)A9#!}Rnqoht~anYbw{jHpNpR88G&ZVEDsw5N&VfhMSWFs{)4`3OR)5+lp zh9wIPIRs4)y=P-z&v?H3aQv0Zl&_wY;lk}^^}tmQJKC3)x$v^5w^!B0C~i#QYxkz= zqgv&;(?&LvLQAsjJf4nKP)?>Fv&^XBzmYc>y1Wyy>o*kj@hdeFWi8rp8KAuZuwev>%%+RJIN1>UU&SA{#L=& zoPO(jB>R^^$~$LPZJ7TbX>S4-)BgXDA8Xu;uIpagrLo6F(>j%wxd};#LbgPUN@~)o zQit0mgh7jjM%QXV0y27;Y8*5W!s(R#uVwQeqJ-wv*4$Q8|ij;l`3PbE-CmsUKCt= zW^m(tlJx@qtgrQBr$FwvIs!*OgN2+?#Lr+kdbn@1b2FqkyHZ?`gD>FJ3*{)q&D`~n zjU71g;^k;#XJ)h(e|Y&i!yVY8%ke`b;L=C@x#eo$(gM+eE8(F&^!y2St`D5%0tc?Z zNg{3WnK?m~pc|TI0Ir6#gKSSi5Hvm}<0p(8J8=voH)--uKaT-ykCXf< z_y*v5qVR{mKx4t1jU7LBqTD#}&sg^{W5-P&4^3G3tBS$)i8Br@I(F(e)hoB;et)ud z@k_IkZ)!8GdzZNV-M7?G-Tdn9r#9}dG}bAG+({WWKX3zQO+WHN5 zQ+Ac@Tt1i4$b4Pi)Nki``g&~Yn~LUv!(L}X@1?!{)H0}PWMS_e6c(4BSJ}$a+PK@{ z_}LrxpS`R4KD0vHc#oscx$yYs`Jda^f3DfI_lWQLhzA+(tJ{ac!p8zGCjdcC96xE? zIA^e)>Ep&D98cH|IG%Xy)D_iRPkMiQS@Lc1+TYEr-TKs)s2l!0^Q!sM+cr;M$+?$m zG^`7pwIc*bXZD;2TTf|2ub9J$zzeohbG4;N?WSiFv!I>H7`z#x8xW-JQ#=Y&BiU zp0$NXY$Yh~@qsrBpwQ^GcEKTVPGd)*0D8AMNhwZYy6s2D@*}t6=9z~<-46rc07n5- zIKaEZc)ymm&(Yh+({Z4Coa4}0 z2i$#hOq4d~E}F?w@dzSLPFW;N0O1a-Xf&6YADAa9A;4rB&_0 zVB`volm7L0b!R#FIbB_Hag|e1UYM~_-H^_Qx+6@ZXbox^-|&%RyFBQ=ep|^ z-{Q=uRv~VkBzaTLfOT-mG)HCnL$BTv zvdOQ$Q|pLqD!Y|!$KF0h0L}KfS69t)S@YY@4Ei;~&$~~BP}!6lb1#*?Jn36pKOAlE z;8hg4fw*vJJA=Ut@CtB%i#*sJAI@~=GK#k@!9*YOYM;;ms;uH9)_A4I_ z2Ct%alh|;M0_#+l{86{2nyp$V2KDNTsM&opYpOKW{iXwidH=?P#bTM> z*B#BZfq4ob=2hBt!ga#Fzz_Ndd5aUPkDf@ld!xIjg5L0sXIcvvZ`k~)J=1*V4POCd z+76oPHNKV#>{zqz+kTm+dIDVeK&VIf_CB4Kj{Kbh=(79G0EXi5g`C8Ps_+M^SPsyZ z09veerDAY!e;kW&r=RNgVvv@$H;Q93Po?LvUuGlavWrV%PomPm{IxB9nGfUr_a&@t z*t0a$kz9Y(n8*q*J~yMKkIg7pSYOeaKlSgmmZU>w)yt-lv4g~<0v>w4bE0J0(O(APiD78$0hsb zM(E1*74|1t`)zB<*5=O@Kz6VF=qCNtHIenFdTibmWLNF^FKHfmKKTlPq^i@CY`U-~ z`IT%rHVn?`p=w=eI}XZI$39%tfGbb39FB^x z&6E6I0FiyHiUud%F~}4^n*w<}C(Z6e8v%61jda+{>weqQV*zWP^R8FR8O6^DB3Bt5 z>w(v1Y)HD-5#e(EQ5$Pf$L5NJJI_m7dEs|L$!6MeoGJaCdvrHW3G6FjMfptJ{zkz# zXMZ6GDm&M`**;qwTMQb+F=nd9tD4-7FV|E5uJzv+Pq+E~gf}}3fL}7(w5jA+9NVms zziaFBSGT7w+A;G_xS^&&k2o~V=T-&BAjq`eC4d~?tYcK2HP_(#0O4#m{~WMLdk|x?l#fdRqg$&*7VHOpXJ@9SDe5h zR4Xct`Fnp}o2p)YEUU%C6tU+Ax2^AA5c}-SJ`3A*7f7b1otK}UZ`fOYmZMrI5kE{l3v;u?q-6st$Iq-*mQ+t0z@|>V3$`Nz6MJ_@w3ChT79g zvW9ATarb_=UWP?u$S3k*0i;sgY}Dd?J?raK^~^mvw~}J$-Ab)23j$*$r+85NNoTg{ zDPmq^+9143eNB$qP!(05)j!$Mo#O56bj;a(Akyz_=Sw?nWITVoo^R$$Xg}y%iw7$Re4VWx$1C861-r~=uGmBdSPCrOW zXs>a!cB*>hOm3N5y1OGt;A^41%yfbCtqIBztaRz z1bIN6ZO{LS$o>D{0oLv(|d{68bi+7C>4P*lBRvEyiWAhIDvv%Vqtd zcF>|Y$UAD+Njj)xmUL18o!>}=TgM9^{e{1$E9@>m$Gf3n>?DAeI^TN#)K4d#aBBFA z59f~rKBa~*6c^?b$v+mvtbFh4TTN{)it}^^7mbuoSp(whm0iCU61gEC<_wbVdvNIc z9+vy9PI|*79EBTV7P?QUxLEj!=I*SQP?6M~n8G=G_xx_SaS70pcLeuFTdD2E<#yX` z#&(X(5UQp;+vaa{uBxQv>BP0UgXVnKIHnrck-bY797}UX0c)Ce8=Lc0%%^n&7e`r)?`z9qYv=;>hPRa#kjXC?XB~-tL)f-6ML}W=uPTe z>J-XpIp^C<0kpPT5`#W+zHm@U?CU0x0@O8#jY^BDXHsJvxFHqJb6eoD9Fq#g{uF}Rjcj5a?Du`Y5oZQ>DxW^@ zn~ufP);s!EpIiLuS9A#=dp9rJ^g4n(QPn4`_<8Ja2i!D5ylwAHpSjP({@}Nt|5VER zXO;DQ>XO%eayG9k=eUO1yqP^Es5^{HvyuyjH%N|96N%Rq026kUnY^ zvSY|A1ds-o{;1tzY>h!B`3pH>r2tx0sk2^@%XrpLpq-SRZ%W}Eut!jiC0E2_?&D)2I!U985U z+mS(D&sb0AkIx9}*xXM%43Z1EydL6X&Kv#{M^4FTL z=e}J`nl(l1?hq&o`0gx5o@vgrvYPw@&d;3o*rxlGt|n8L+xF9&GqpeDe9W8I(Z|va zfSuKEv>b#@>Fh_D1!QI<`ASAtUPaPCLC>FGsKYr``M=ro{q~-_P38N}dtWv<7^zt{ z44Yq%9eikbUt`9g34iIp#f!Xqcbq8hhunWJyxTV%n*4H6!MrQL1>C#~Umsq!N^hFB z;qqtKUU&?gfzZS zc6_^ik9L4gl;y67x%Y?M>-&0P{Q!5y+t?;5iA{U&`y?^8IohDJ+Xb$FMeGJ(Vzzt8 zm|viqWErbvXZp|Jr3-CKbBEe`dW;3o`u0Hn^>liFFzK%b)nMw^*?H&cZx5Ibr_}*G zTvesJh&n#L(8-g+@2@chXsR;ZcqU;|>iZ=N8PAvaj@8^!=Bc;$tK%>!((genTtPQI zZxRnT?cd{~>-9Ns*4YE8v$&06t=H1{S%m9rhO0Sw<5fY?{oHQA-G+Pd0r}-1^;4J8 z!NGIGPk2vw6IwC^(Dkf>X5%;12;Juo95k2sTL0X!C&7rz7_jEG9JGH!8={+_63IzT zrGAP#*->MS;yQ>a9PPw43Caz_jl;%_L{lnR$CFxkKa0oKiwm%5KL9_gpsR2rTc}#> zo~?}Ei%vNvZ1HsVj~m{e@1FQZ{lN90Pj#QPY=-#7Y@ak=xl#i2y#B!oPx^BHHXrJ? zPh^vJ0Tj+R$gDiUb4@EaQaSfiq)%K`p3kZkzv)L;#(DJar^j)M*ONnj_s_*E`v)PZ zW7Lx_L7FxzW(Uik26e9{yh=V2RthT`c7E(^&uBOFb8C;f8@V~+oDYG^7y>z`_2*k% zyvgOcea$V5fX`m`Ego6NhUrI7Vi-@cmiIMy=dACl~b7>4O)SNrhHd50ki}d zz*pmV_-*+2fFd}UuT#*G^F{!@J)uwTzRR)DJm#AyfC3+fJRee3jATDy%5m?4DutKY zLvLTSnQ>GA)faqYk@cOZ+8zT9lN8p$gn>NDS_0?pJ!H*|4eEft_!0$XwX;B ziKXoNWywY`cnA0qK*y5=&;%~K%1`Ct{Tl&maxQinIrgn1n1>SksvnT6agJ+;IWa^yLctqV?ylC0h3W0_X{Y?xOx>%?0-! zdd5P|7;D=1PxQX?WVU8>n##7ga)X<}U){`xO%Aqm^92y?Je*Ak5kP|=Xk`Yt9VmAX z%Hwsk@V_{Jg=zeOzWOGMrkv;On$|IQ+FG0y4a&%+S;Z~#CKba`aQ8E?0#9RIdN+O0 zEa0s}re^ZAi~y^e7M&QU$2zkIW8CCFlD9MEZUj^YSn@4=2#h47^pCpHcMR{<_`+=# zFSl7*=JUDFp795bir1F4otgfvpF68cJz~=LC$sb7I`sLhdoAnk^H#YZ$_v#Xma^sF)iZ+!1<*BmOa>gC z6{YPn4HQ=8&J>UM*w$syo|+XrjdORGWSRNe^EMq0GpTBvcIR~)XJvMCN?qa9We+bA zj5?Wm&4UqdrcUr>71p0w9u&W*we2{C+m!NGz+V9_Nz_nJIRSL~!?be3*Vb>WAk!LU z0W>}=m-q3wBKPZWBxb-)pJdh_aIg!AY#V2W#}C>DeC4kRGwfVPe$hPCp;*hOUGfN; z{YQ3+O-jJ>sT+oiH>GP1pMF(S!?;9zL>S80*g)lP+Nf%F`Q+2Qvo;Ok3?GnZH1C+X zW|*A`!dJ{5<~WVY;q~1YDe-rIeqcN=gIZ31_B?I4{L0;{cinu=)(l@Y>d?s#IvsUx z3iTa5EQ4^xIq_g=qiV75li0%dZzxW`9W!j7ozS&s ze0BXa#Rt}5SQ>8L{BfM=i6wg{zIt!!@8k$Odpda@NuSA@K09%B4e#^3`Z}Y(w?E08 z^Vjq@N~W!4%wR@CE8`AxMxnx{xIgwe2Bh9Bp*6hUqP0^d~)0o1#soZh&(-_)KAoN|8i zAi-JyHR=-xEHnRykEPPQC>ST=`}J^mBsZjNl?c()R2N)QQhb`ug)Zo-t=Q zugQ&gH-k0oeq>8m#dk;<%0CIRW~Mx7IE2PnWH7xWlg>ontycJBv2OCl zR+eiXp(}rx`Tg=K+n;MiWZQadf6m}~TlqElQP@Lr&Fdf22Uc+dy7vbwO|-Z3$bH1r6VF?=%qYwtg|!ff?aD`d6_TcSuQ`0n z#p$;a`X>AJQ?ib)1F3%@kGM`k~23 zXan-g4i4T2NikVIYt5z4NYAF8&EFMy^^MtGMAzOVc0QSVnI4fBvagphP&WLLM-Noi*>;0q^5>K;E7EksJX+_5myA>QBQ1kBl}mb;*N|(|P4oP+F7V!97YJDvtNj^LAOD zt`4+{oxycq{LEW#z`-bJRn^qs@R6!sR4gGq=s_&jJA(_@7fG#mO@=xGCnmm;guU}F4<-kMw z*Ul>~0Y91E;#T52;_AZ|XyW!H!5htwr za*oxNZp=|O}*KFq0Xo2T-#pXV9*Ay#my)!>}U_5B-fyRCZ^%&6oC%t^3J zOJ-X&GhHWMORK&Y=kCmzVO&(L)kN+)uMhWbi2@HIYxpIJ%u0&n_{S$s2@pW6SaxpI zT~>PWVJ#P8Ii1Z)icsp|K4(*#GEeHq-8?dLZp;n1D}G*|F@byGi6i;*yl%Z4g&bO* zkH1dU7SrIkP~yNE0c2|n&#S+4(^I?5GAMIgn*!@1=!_YHpnaCxB7k0~?GZrt=cvi0 zlHU|J-uLuR=C2?I)e*Ge;v71|oSh8HMYaHHADgFf;DZ1PrsbJ^*8^bnYZ$#hpLNNj z*6?$`ygV?45HbUTHM6slKnAdkX<2R0oofaBh2}thZQm<^JP466^B;0J$aCl)f~iZ7 zXzut3tH9pQ0_eAPuNS=iaPe-oB6s33ezDU;-55gS6(WuEd$r+AtFim3?bkBtCWCu5 z_HJ{IIq5}w5cv9d$?iEwOBT28%T5_e;lSm0e$)u|%qUH*F+Q5Qkz9ZIi&5J<{ip}W z&lr58k=CiLo;eT-J}vF=F!BHtG97)Wm-+;kDt<#uFsM?{OrA;D9=0`$zv&)d#rd>x2XOpjTuC^>TPwM zZ<@`V6|w4cdX#R9O=x@Fc214X@|6RAJ~IXhtP2eI5j{U9xGH1Jz1+Ng{8A1fdHx0U z8!qW#-xZ4s2NNj@2~`jKX7Jr$9rR&3H`h20_}^Un`CaqA11!+#*Z1zq8qy^&1yCK`Se;Yg z$Ju8x1lKv;zw;~&IJCP_!J2nDrzY>!S+Z}6GdltFqQ^51$NI#v<%-ijo+*{bPHX_s;1bX&X1lNY%+E5@RKr|kg^OaUp3#I$ejk7AYZ@b4)qWpac11^ z^V#yTS{126uuh)r07Pin*1>l#k{}rZ|KGImEie?54&i6 z#wYZ9*~NVS0gx#~7Se`(Hx)qJW@`iH zJ98f10RC?4%+I^zdnVAFePJwoiIVB1pXH=HB{!^V@iVSj)>l$LtdI&aoj(9`#O9VQTj^jhI{9#aU|)GA%?9FcKFJdH6#n!WEbMa4 zZ_7D*IW_F^t?#}`gH2zR)c3qyyyS=ha|y^9&caM;<*dpzr}HkeYb{NdR+I&Vl;^Bi z7E%$yg7+4xb7pMO-oqm&w7U6eerDUb2h|Wi9tdid&nLd8E&8H#tC_ISp?U+5wZ)-H zS6lg4?OKVAkyF+z|E8lo>{3wjRsR%=e{~?4b$Gkdht~pVvV-$q)7FL0u$)aHZ)5A4 zGs~FvCfrEIwD^|D=6%`Q=^weNcli~~{q?nZ{J5@s{@SRQl^uufUL4>T!+wcfE+uDz z278UszG9V#_Lxd=H>iU|M>c;*-r8P#*9yMeC&`RdUUhMc)k3#2rLGTAcO!Dok-UH7o0_u7;1s!^oYktK zSy1psH@K^S9t%;aQnzv_4g~Z6&1e(>LiwmxNo%*APDq|5{p9W}23kmYRO1y6zKk z)2G=%vA;QTue5x;+WmUc(Bi*3l`pcBYZe@@rq;>lD z0JA2rqlO7l16J=j9jDh=MKy%%{P^6Hr|3-Ru_5$@)@p;D6y5ghh>Eij^XREPdgr?) z+tB{r!iMkZwheQlGuygF`y618VQ%ARpFesI)wwfrLRyJ`cEp%}x;2oJ5Ky}BkB{;_ zdfH*$R4%>dy}QlaQy`LA5cb@=^gw@d2S+~4y)}uQTfd@R--w%1nHBelz*=#Woon&* zxn69)ztRjN{<sXf8iXo}@p|$l^U6MDgqNQ26>FYv!3@q89t6 z?-hgQ+C>h{${(U~{>Xo>>k7YSapv6bn)dn3~RDq0Z{_rZj(|uH~NR zmT)VWK_K^tAiw4xdH#jpv!!%3&-6j{J}^2$c-waO({nru7DI1!oRXGqE<2H)ta zO?RCSb^9E?l|%FV)@F?47!z&E+vD1ZZ83SgmQ+ID4o_q^uj56z)g6O|NmJ^7ve_W(p^r9Y?g zs%TC2YJoe$Od_dCxfyhmTrb$+aOa0FyVDhGzxciE2}lkAiE0tp_V#J0tF9@uP-OJ% zR|(+PScH<}jTO0>b)ZE7%7R>-i?dQ@tI^s{z!vW9)$&Jr?H}z)qvh3?YUB@)qFV`n zcKk9tOuW%wyY&m4SCQSR`iAvpnah*rhA#!3z7FkA?3#&>vzSG6=4HY)1;g~`&zW*D zDfEPD&`gYZf4qkR^4AMqCGKG=%)!tpl4e1tNqBxdL>@K$Ij=d7QBA@VlN``0eL} zF4I2uUQTX87ahb&a;@Ac;1W3kh+*!7q?G`Uk+d@A1EJS_sNGWjaeadsiyyAvS9Bq| z;Pb}blMMM{zm*9V3@4_^md7cPX631-tJ=NN_WEZzuSzyvn)UbcM(SWx)T_!3{ds*A zm0opfA?p!`<<@hP00#ZetPfv*?+!cg{`w}pm7MyLnOv6vZF-|3=YjkXJd_ue81xw& zJLB~Gux1teX;wXAQ-h;=xnp|fFYOLEAFzkN7JQoJ73cH!oNa#zmu9{6t>0S?0^*%> z0eQn$dN;TCXGaHZ(p%iaquliJwsq`Z+xs?W35yj{$2w8yCEnZy?hR7aAvL}mr_d@A z4kdx=5wW?lW!IZ|2PpS_XeMV~6;b-@O?e7E<)LbdJ&UPjpp_V2>{XsRTkhN(Uf?@j zN@~Q#0}+dtO)mHCB7CnT2Y;gv{{ge#Jz#(`F<8S0E*YlqLhM!eXEoMY5vs`MuT86S zO0N9+>wsr9S^irrS@_#Y+-GI*7czk8r$^y1Ppe{%T)PcF*puE)>$Cyr*z?2Rvg+TL zAb@rVAREHabx@4biWx>^uAy61dGt+@_z-%YX1W**W1%BuH{TKi5ls z^p699MUMY2fJ%rCjThI#w(v%8-c%4atl$qm#k|>$^uaBE>(L(&@&@J0FXU8sg{tNF z2_RKMA5oM0lKX}GhFh{`53~Np+Z+#qdB5{&=R^HD$!){5o+aA^P)?bOT8G9Q0YvSb zmYL#bqm)L@y3UmgbDdwjl?!Y+YCp5SRWnpRk{jPbB-T_1KVRjN(!sVr)2)ErS z*#A74>!W+QH};ij74L7bCIa_S#fd9TQ{lq7UH?=cj%zJ==oh?iGJmqg)@0)e>G1^4 zqx>bM^x+H7>%AtPZM#Enq-77#Z8)pGKiSTu5Y_59QC*Sk4I!V_?XO=B7umPxZ36G= z&y0A)b@4RzC|GIA?zq1X;AF^#LPE-%#Z#9O-hTV&XL{MXWDcXbm21EbVH4R2?6&61 zV1_PQ^-E&B*Kn|-a$9IRgXz$C-gs#!un=#;z2GRieTT-{1=a*_+VK+wpZT9Zo%;Ii zy45vPpLW7M^7T6KYf&*-q+x1HeT)CS(@vb{rq}xuG)*Ep_$ps4dHc$!d>>GyTnMjh zQ|`DkP|!*J?oUp3^#YhRy8v#=8-LH=dsI)bj-n4zY((AXX-_O1}_9b)aY>N%n=Cs9w`oLJDY`6l5l21^rZQ~!D zVab*+{C&;kQ`!ZN-jjH>U#x>@VE)YePk9D8gcX_is%!T5*7iSON{26O$2t1lZGYZf ze*NM)UM!)Mo)&O`E#Z3-HVE=)Tb z^gStO(-I5vlgB$I{CaBm`b}O>#Vz1g-o5)(E;!%Q>a!V`!MgKe+@Z(0WA;Zvvj?ZW zKKfqgkK;xy=}n2J*(I7`&fMDgI@(Hy8Tr1t$+iJW12vVr`uJnVc&!u8)#*>~rCg-@ z-0>+|kZ`=BL0J~X9PkHjS%i^47_kW-KwRn10RjD(wLlQT+bkKkl8MLvLJVRcj2|hpJrPtf8E!>%G$sgjj`b zg*}yKbj$U~-%TlI7lH`QBRWN!6b!S1Dm{w8o?_Xf$1M%|rANMcU*uYo4Rfez**7({ zkHWh^pY;~Jn%ugS+^R^|&`%&-hgYV|-&E(g*+SnTLZ@Igi7=F}o<0M9VN^^ScBw8u z44Mst)bjp}X?0y&T(h(sV4d^&{*&gv_D{;nilnqwIZw&)El=53xILavy|sJ)-WtQM zcFX<6paSgR68flXHXn<7_G;rF$%&DN4OYLhdnDSZ8_f^*F1tRM7yfN`@Dg1=W-_Ct zlIg_A`%q`Ba4xgFYf8k_*Iy#EC=L1vcWLsSzNg4lZXZ?$jESe79{O(SedK%Nqp}-> zw~ZgX$&ib)OQ(|3&2s0sl#JBSjfq{|2R8*c7KQtnTRfaHObn%O`2Lp#*ErEVB@MIyQ?B}!4K6Nx z8}eje&fAY1qYm%v$j-Wl`*>fD8~F#;xA5i)Q<|mRWX7TNa@`hkvvmikb1Wu>u2x+^ zZg{wc3p2}NJTs=f$crT{g@5W{>h;`o&hie9w^e6~CJ#o=LSa3(zDT~i6C*n-j2&~L zE3Ss{k#M8L-@1v`eWzj}we&eabppr>1B=F0&tG`P>Vr4`7U6C2RgT?FEsb%Cy#=%v z>-3e2ya+p4S*}%=+T4e9e!_ay?{yW9Z02>p7;jg6csn(qz<=|VJR|3iV`$~Xe9*ye z4&pXgv{bfiOf6SZukTejN#d^+DzPO!3NV4JRySOrsd_fep1kxmW^U(l{ z4*tH>=>+AySK`^$+c}z_1W+v~Y2UF8`2`xav3KY6&h`#?Y^g~ZbnTkD;tkhQ{~+s9 z>(_fe7t)6G377k3TyU=$$Q(CIxG{En_16sgvy}9-w3znx4%V);!9L?v$?#jP20l}9 z_A$bjo*|}Pkb?2tTzWx&&Py)XLXJ`dnb_mB@)He>jE;f^%dVCSTjIeKss)7)tSJV} zk!lW`+Q&u(a430Ke7oeIWL!L$Rda&AF37##hLOxa7RR{5i0z`JIRDa~F}z{1f@8(G z43MD2_%90N`@9XWbkreEi)@?4Ov^Y{_!Ti(HM3u16e;%AWe_KWDM&g4BH=(w&Nzhzt8^eD*0v5qV)&aZV z_u1U4%!>XF3Tq7LgqZJ1O=4Lc7$ASSKwzk@58?aTNBbGv>UA5UT>^7;UEcNq`*utk zwi_OQqJBlog>~@H?|U2ChAl5&JK6G<6cA{9@8aDf0oL@?(v+!dSeE78>zz}AXWz|u zMqn1L%FuFa*0|tbADdt1xWUoYhWcA(Vh-yIA=HZb_W_T}^&mfP*>#K3RH#I2+dK8t z`5v?DWKeAs%W?HRGUN|uZTF$i;{;a^Ql5lArQGOcAN3nPM_wm@R+E>KSCdyH&|9}L znzLgY4PUidM)`&@<(orW%ZL7;2*H7U-k|To9kV!8{Oza+ zyL$yiK8}?R7-A|Y9Oh$=U?uoG`VlpWD_spKp5R=XHaLO?F8@NV`9iO+L$3KkUX8f! zPWW@|cpLh+t2L3kn>>~qsVS)_Yb$H0k-!y9=(~}yiy6^(BWa_TF>M9c(t-B|cTXWV zEN(mGCcF|#LqmA|A907H$5FfGd@v*hZGaX)TObN#3wc6EAv?%@h188o5|>tDoM>R2 zsHiBZsHm%HXeo^3EtKb5CA9m0BLjZ z6+#Zk0=(J)8A68AGLg6JTuWU~!226CW4u7F85vF@d1 zB5`4-jA>%rA?m=L1Y9 zIY?;^FsG`ltfsCeVJjF#%vNOSn*mDBKpKd>ECA+60k52aR9uASiu@GeMyNo@PFhA1 z=VUP%seq?e2$4h!F(4H+lB!5Z8YEOLnEQg;{t%I2NP@HY180`;sL_}_3>b9-pNNYi z3)umdU_A=v2)U3F8P2N6)=9DkMUpWgbCG%uK}V%Uf~;!9yK8HZ)PW$xCV;*lrVwx| z9wG^mL2LkOcLOT$1}i{Tgus=gQludY+*v51C}XIah#P5Xsi{clKng;!tJHBFU|fx^ z190b{6qmc9wSYG}Xf?DA;Jhi|5(k)dfPZ`Nxdr^x9deMC4?EjpK z;(Q2KC?Ox2_Xm_+03{C~FA9*C6QJw@*-KNEz|>J>1juVkIJ58$X^}JIcQeaygXs>t zW?7`W9e@MGb=-me9KpZt;9tab76ASn!T0RID^KvXv<`)`#iWAqN5cGw1jM7E25z_% z>kwR^CeHRDlQ+QEgCe$1D)y0W@BJd?1i z&@m9iZZXF|5Zug(a4F(T)|wtmWsq3kC-OZF->S7-b7N@kkka~F&Ls@K#zG7&IxWeGMYfqPsEu4 zSh1JTauD=F@`OV`E3QC4(&@C&WzbVdh@_?=5#^;)A&|ZcB_Y-lRxzMSx|U4Vh*k0+@iUTw5lpVY(5m+!%NpQkjg7fI|L9p`fk-fKR+CRNuJmp@=M^ zAc<|*3Z>*Ll!COS;a)40uZEVU7-coIq!MB5LVDcNFg|cg!|O9l+NdNX_(C*}AmUN5 zdc*^e6wnRG{ScNzxq??nVn`8YAV+1;M##xX*#LIc#nMMLERvM0#>Mf{6;MUNi<%|0g3-dYB4cZ44vA6~dOx80BX00y*Z|}@NaRB=ItYs~X?-Gh zsU!6@rcZTXo;a#$NuipSR91|y;0OAY!8miF_Hcb323n)HDQAGY3@uCwj=KEEh-<8)tddk&_g67tqDob z(grXtfm~P}k41AW$#|%Nty;vRv}a-HFXB;J6L_`a2|P?XnoCD-A^nlkQPU;?tH#kx z22U|u7g62`8Gvkj2hfMDFiSWj){HdfNMyv4rm3L@G%s2u9yL%+Xvk##hxn&P|z>lgljDwZpV^eV<*qW-w0Vx?$3c%_PT{E!%nQ?-E{ zz;{5E3M7npDpI{7@93tt&?7tL{^C+5Vjn3 ziR=O8UnFhWtp5LzM``*a5D=q}_>3$?+&59_iu7ynzpRubtfeqZlF6S@!`0RROU7G? z$|wq9RkX5Hb&suI#GRA|H8f>>c&pH^@UDos5*tmUxbAF)I{TLjnIzmkEPWZwLwfQ^eTPaN=`EmnKGKx}`Jwdck-r^{I?`>ywT!OsN3xg6w`Hvnt;7*s zAoU)CkVv-{k%)t^PljZyVoX6A(s+e}Y-tF)ywV(x$SqOl(vqlxNAwJ&(OV{;-Uc{B z>La8Zg-A_|-{PntL_}#mB=A}S*Fbavc8W_*Ca1=c8OyU|^tK(KEXoPm8Twc1qob;_ zmbfA&smSIZGIok&S4i_8M|&iPL@G09APIDn0P$GSCV}+oM@Lm1QQn7lx^TP2aTCXk5g3p5;e15$kc{4Frviz75)zV< zh_DBVaU_HO!Um?AwyL;~L{gEg?nx@Bf1_4|cY4KqV|v7-D5FIrHjdhpljaVgCnYbO zDY3PxO6O7}*{&*LFGvRk&0mnL2HC(uzJqp_(Ha}cv(P+8ranMdIT{aA$c|CPw4^HI zBZ$o$0V_sq7PniZ%PZ_71AaV&85e>mNals$?E=6d+66|q^+6CtS~7?{rS&G+lh+0t zE0TIc`N5*L3hLjOx8t1S6*S%%#`GqGI>@dH>R+(vsU|8NK0ZwZj4GoLsg=J#pz(0Qj_V*nEwDp4Z-(qKs-e26iEacg)=Q# z&V*D(u_z6RY7g7b$1O^hPnk&lBR(ZLGZ)5dWV8s;rKr~@DMQT>oQ{sx>R@b96x5ao_i zo`Kn@$TR*gYZ--8^%0zo9ut7SNJw2eCdk+aHXHIkaEeP*(o#m@QDp>=BO(SmS)?I3 zS%hX|BFn($pF~`tlbXmlDAJKYa#;k|keUI>BSjHh%BzL*K~lbh(Usas!6;!~tuBMV zvVCtct|G`L-Zw(I5?degQ)}Qo6k-00R-srnDb1rq#E_{$vGFTpI~(sns-fIrS)ZC@ zwyS}!1Gh(PHVa29nQV8RFxDbmBD;@BtQ|QQg-2jK4;G@gH1{JS2+p+FPt;{1i0oXJ ztY!}hBOX%Mpfg$^j!4rS5g{;|$UHJ`KO~F_u2q@5X9t$+dV);M0oV`7@}+4=!~;w# z`0gY|Oie;7>QcG5I*J2W_JQ*;x>m4xI+2x2cjEA9iPW6v>?BgZN$03S+N0RGx|)Or zq~j&n@d8?~PeMG7KSI<|t%F*Z|djw)FU|x;pTIwhtqSZ>*LukH$cW@Bzmf8^q zW16zL6{ZRmakhf345zOlU5o5+{adG7 zeMGkclQ}Z0T5&BTkPhej04r!`Q_7ja`Coby1CRI)!V(eaW&apB*O!T~r}BeFVd z7X3#Y$mGtFIU3^Q|2kVs(inlQs07p{{2W{3kLb%_yNJHDq(@|{C><4K$_Vo=Aup18 zmzK0lB**vdg-8veBN{WMW2D9i1jVRISeu4)j08PKVT{D}D}$g&U;W4Pc_Xn+IAJ_e zzuKC}kT$+bhbb#3u{3JIIO{gJ)NpzJ6dN?YCtgcQm|U0Yoo$=8L6Q~7rf9(hmwF{0xu? z!?u8VHAA4$ZQxMa9-wVxe*xK@k|RLuqcC=lvT8L6f5c9}{bz+8AB2ikgH4VtM)xRy+dZ zb^v;YGFb(p0f}9A>6MQ_Js}SyO;vFuz-y!*@F0VF2sLNG0Xl7f<~gz)A+`H4AP?d6 zh%`SVkP+oaMFRJ+D(wfF!1nO|#Scb_1fxhzbfi;?KjFKNv=j{$Rq>9~h(3#ymCEj} zjkMAqOJ|fbUHCj9A|^F$b;%t->~tB{3&Q5jFdxQuI!D*3>@?a2VFw7A0T9h5OG{-$ zc8Id0fwZP@iqiQLNmdS{WW>@mMny<9ZB68yGj0p`yJA@xCIOKxj6wsfXf^mm=X4N@ zMEb(WuAk)0!vbg*czqPHSZSU{MN6Otaa|zd=m(OPK}+erI-08@9XJOeXTmvVX%3LT z$Lvw24<&RQHEl#Zcy|z+e8(*U#VlMuSbjGupZF1O2}z=-Da14D$i5QZn?Yt{rLj&( zd8FTfqod+36h76AaX`W*t0ZV5=q6n=$xs;`QPq`^-9E96V3{o%#bwVFjfP+UN^^7s zRacg%jIc8XKjPp&;uc=Bh<7{@gur7eZX@XP8b+C?CyhL5g?guoMCK-~?iuC*&;U6~f;g zVQpYq3+d})_AYz6O@^9GwftWQIPyFdx*}DHyh-*%kPJl>A4S%_8LSTJcmm&-UfU0F zP(^%li-ess!|e_CUK|x=BKE)O7QsgGo&^%Gk!%_{*N1o_GLMBIB{DrGoPhz~{ZDI9 zmEHXr<;)d6*CKpk2T+?Ts1|epvZ=NjXm^4+TtY;Rwl;bPjt}+QA8vM)Vwh{U;j2L&IE0B86Si3UQbe(H zVj`mG+ExSMB2&7^9wO2`K+n%3HND6hP$SfqdLHTG_lheICuE7 zmPGuR0E);=qVyh*jI>9fuaJ(an$*b?yfcNu4t9!JL}xuPC?s+rz=LQMokAIjrpUev zs&g40B(hG-AMlg+fEjS4ND~>Tz}-RWb2E3q?LL*Nt2v78kpsJ>#Ek36xqKRkK zGM0h*hlmG!egc;=Vi_{JNB&~;m>?9iity<{BHc?vA^Hl}J*r(?I=DBWy4S>>AtB;y zi_l`xlW$_1wFR;{B+L(xOhtV1AFo&b=jY4-O^-6fA@`d=#u0$>h+^DU!1xu>_eHK!QE^T6+B> zDtgq9wIp^#WKQIWY#sA2nS6FF-~ykfMFOf1cr7zkfg;0*wX3OWDT}0z`z^k9X{sa) z?L=!g6WT4h%Z9`gWc5gdaRrh<5Bb>R)&F#3&q2IpRh1kAY7a!aqT`8 zb=0LTiG~yx5AY~G_XTKqY3N3AT}wH>582E|j)rJzt6CDb*x5QB8u49xE#Q%P;Frya zW_IorPd6Jo_XTL$W=8Qi!BcID1JUm?2 z5Q*O2-b%KP_Kr$66lbCX#oL2o?de1Guyb=pfQ7i0;$~~-CS+3C5)iiW*r%$htOOn} zqpqo>xd5DBR{{kxNm)tTl4$N}?SU|`+0n%bWko0wF)tFa@xOU-_jGloxOoum-0j@F z9Bu4~KVS#!%>hJJ0<9d7U8sVj1Cir@vLX>8*B|#VGDidm#A9Tx0-ivpE(Aib`VBy3 z;JZ6^sDkg}TeLgW7pSAI4Sr*r8^y-l&SM{O+qw+EbOwm?dDF7_S{3sg0=wDtAfJ>2XLIZyq`q3+u5&n}Jce)nftl$-xGapsnp-gM9O z%sbD{CIiFSwAa@#B;Zs-~ZRz=wP{rdWl-YEQIHO^Ipq15L{?<=iTUky)WC8z8mlm4 zQ1F!7cQ>jkbVjAtPYwUOU13L2%Zcqci+rH5F0v$whI z?e$^i>76_72Tb_9#BR<%l;uVTZaK`ldds_H%EK)cDW2q^0xQRqbr-#soVcoJ5T&>M zqVp~Ck*CL1!&gV;2lU1pv=VPGV7R3D?_>KM%r3Foy?-uwAT8_SXb3u-Ra45iA~)-=jM?w~Y?2>rsYqBjx$du6->}le@m#AZht8VfXAVA7}ma@r<=m-CUjWi4&B@5naE$(|h7Ar+NDC zNuPBRGAJ8=30_$N_Y9`F6)K*eZ!ux-5(j>F&9A}N&1P?2oM{{}-S@ra6_&iiRD;5C zNhfO_Iq%ZdR*&!~49*Yz>6eXK5kU`vsweE;RXeo&-qe?0-`XqO&oE+Uw|$ChUpF>+ z@XiNLVQZd_Tk7M8-{s{EvtzP;l5gFpQ=I*i{QV_+IxnYoZ7J&}={tWacY3{cbH$^7 zu4bLy>F{j!UYFTF#imy}Z}Ij!k{B=NtZf*5-@D(#FPM_tcIc7f&#}j5>g{ou`C-k= zPm>J4cSg@0o8&l09pX=1TQsx4@yWzfcS-*rZ*Kxk_4@q*6OqVNp~#$hIvi7`%<~j7 zlPU8&&k|AyWeS;RAw$N@qJgMnRwP5Fl$r28-*eo1b=U9ayzlz2cipw>p5x?m_Ves# zfA_QZXYUtJgu^M2fBf)f{5qH})Ka`fqh~QwZCyTaC;&IDQ*R z-jIlC6QYehk0;x=op!TOzhku}#3fH1e>kSRUSCIY^_+ob&bKGu7k9Wkh`N*ty@_>+ zBe!ewD_PysUt(4~r?`5{I9we4eaDE|ZCZQg+ap}6L_`G+#XnN`{Z>OS=3<$=V$#58 zu}^ER(&y8Nd_3NDe;6WE{g2X&Mb{@ z`Q%3P>^^_rrEwkqY}ZViCA&3!hr_yyO(WcYNixs#M477o&5iRXVM-SBuHu(Vd9_d>k0W~ViN4ZmJfa36b( zLGqo-msiu@jl0Us&4r6y2QVLz2prUHHbYV!^;L zY~}FB#ny$XKIIDCgyK{<5mocNK{2YgFV@B9-k+`)4JQawex395roV}xhwv+_6;yqEU!9#;KGJY8N&ZY^PKT;7-=2oI zV)hqZZ?k4|*C>gc%g;{i<{G4&TsY03kb70(6P=b0pQat-Gb=W!JYU_!w=ETR>RG9C zei@GRM4i~?J~XU`vN$%$G7<{fVW%uCxfl(SYFSn|&D!OJ*5X3Zu5e_z3)mZ#9L=4vUDFsIzufU)1rUnbC{qxozmond;s^!%7#tzN)t zuhy@OQ?7~)GpZJ}N(>EG76Tizlmje9HQ|rxv9kOPAE(g1**ZP*va)|XKJ?SMZiU@|?DUnZW5LxMQ6@Q6-UK7d_VYZ16h7(wNfSgY(dqTdALNzN z8rWX$bu~HLcT(Kr=G~KU%KM<&J$zZG5}h>UBq99Ab$$Ej(MprD$HiMeo(wRUIt}hO z=_)_d$ix#CUgyKkAo=W*s8uP*NM_{T=jS|Ac-7O3 z%(KgWmMSGVzJgkYEC@^_%2#+ME17p=dOIarg-=FS*nOlhMHw@F*0GiNmFSy?q^{Ao zH^v2CS3U5ZwX`Hi{z-+Im)iz!A@rTOSyw`SpR%(AkL-zA^!w4eOLUYuvS~`8C-`e8 z+N9!UV_%IC&QQb`K5lmMdGLxGr;6xmTR-k7!KKYdWF?+7@t+Q7F%uMQaDYrsOr-u)nsEaomSsu-K?)oH_}5J zep8=hr7w_YMwXB9iOi?y5Sz&*{^+;Cu`J}}JuKc{8`9EAc(ummC89|WZ}fTVO>rgX zzWebFt2YwA!naK&Z;it+uI;6HfY`~UAoD<*5$68yt>x!qWdJL@ zVf6+y*hx((@nMB}Aqs`&m7G(_6*`jAe(;k`5Pt5+!RAeb>g9 z>3>&j#M8rZ(JrOs-PX49a9m5GtHZ~Ed`$9Sis=PC+u>}Ly(x1W^CYJG(b4iZ?bo|Q zX*g+<*mT3|2YalF*7Y8B&;VD?8uy}H|>tED1 zwAC)2QKd)}KH)3GWO2i#UD}@TJ%<2)kmrr2)7|c;A64Hwb2@bQhq`*K(kx!7l6CAA zw4jAHzv``-alM9C-Xy!CWe;Oz%le2@?9#-|9SM&mU)RT+$Z7K9)~DaC-ewhid3CH# zFbey2x!W_V48Jr=-r|drlM}0K8a?~Y+j`@8x7^lnVMB~q2Y5xNUWsxl8K;k>N?qO( zF6pw+71g)QC(`3!7_vT7@%niTO;_A<o)#GFRQ&yVpSs}V}*#do?JF>SNU}x znw{p8WN57?R;B+()AJ+ong4c`LD-7t&}{}@I;i3mIO;er3isoqxWLKqEL~Yn)dyRel7Dt`pxC-rbjril7S`B{h@SM!A-wj*SDT&pHH4Vfi~HP zA*?yB^DwQ>xBcy)(^t<^QLI-QZMjvuUt`w>aH4It+#79}E{OlJgl10pR_sIlO^aDo z|GkB$2k1e|Yp=D)^@=?M-eVI6QW5*-mb@7Cv-lpLexiH-a%rzaJGw@+AQ5%QMw#ux zVpF@pSk2j8Qgm96l6k#Jb|vRM66(6s-`JPdK9$R)%5F>sd?om4<7oM&a4}j8>!lOM zO2mNMcKtI&0gMZ-bH9?GvDzJUMs#u~}Mxu7%V_DTwB>?`*ERI>@Ugym;Lu$;qPFpMg$vaxj< zu{}9^r(4OOf2Z$?fg6;TE?f6L#@c6EA$ zCLdZeq19$WjxHLa@sz69u$aR=o~?MZcEQHBC{c5~)=S+&+FRFJ-dWv5d|yKQQ}Fic z%%>P3Mn)l4v+FzS);yN)tpj*biL zHc}T}-6+UxG3qmwOToDvre+srs`$vnm`Cm=8}*ac9;SMe7z}>_iwH*cpM0!Zieu8D z*Hd~P@>MF`eM(xv%yfhPeBsr1um>(e=PxbCV_WV&-)u5D3+K%X;~htMPWmJoq|n@A`yqbt}1uGZ{-0mj#>G zu2P+MOlUEfVUbBhacsW{PkCT(LP2$%$$;+hwzm^Q{r$IVn3kP2{3GwG&+{%DNjt^y zjz*|WZTiHgF|3v1+mJQL->tQKHtb8+uu{Z`vP z8jfYlY2K;%e#!P+gh=36z2=jwjf?!F#6x*Hr_Xgizh$W4LlnVUSCHs4qRneTknFPR zpH@vC6Xkz*SK7%YAKUWHz-%fPxo~KllM=d*`8D;jhB_^It13RT$m-V)#mdg!F(F;c z4nNdLrS0=ltGQ)=ay1vZYxfVaCiFMVVuoy}s<{MbTM=Jq7@cRl{kCZClFx9Dt~UV( zd@{%&@{I4kupjG{JCv;>L;3_3O?{hL&+=h6G z_HppF;vTcrgZDRG1lY03rtn30uUb2u*0`uL_bw4vVVLlvFU7~A#p;?NkqtgwXRW$# z!v#J`(kEWu*uWWjw&B`{^IC%U)|vdZ-nR%E;_lF7`|1fW*?-_5T8$++$8MEcIU4AxLJ6rxS$(K*} zd(Ly(%wWy_nf#s(c#@bEqkbY@{mX%5pUnt{Cw}_2kn-SbW5m7E~ zarp1=D+$G2v(_NSg`W>F&z|Qjq z>=Q|!#0J_sha3qDUK?P&%k>PcZL4*9dqr-pFMz@u=er0EW*RQtWXF~8hN9sWu5TCc zoOSnDeVjtya83@?+df&CAMXuCcK|V$IMu*84rhBSJ2r7?7asRGN1qWNauN6tHJ0-2 zz;KC0+&-m^lT6{~^2iq1w-pLR((li{`yqT#E7j#bmqi~ou|ZkoA1_gW&E`7FML*3f zThf?EP?#&66y&2k`(Di~<2!k~@3ogNKf0Qc;yH-K%rbmByOke0I7!&>NM~hPGLz!V zcK$>`(rIQ1a)I2MR!01*G?qcxV}x<8l6v`1DbiZ&R5-LpUx;8b8!#_h_iaq*h_=P_ zYDbxhWqrxIxt1+d9q;CCnz{iIfW zj=kGJ9l>ucTPrdzJ}G=(h+5Gyhz&e@#ZH&|F~cVe5(x=P-kT25f3=RreU%*jeK4Ts zabM{v`>$FZ(L9FS_vINqqbR485v% zOQoJ*z2HvWsW;Ahx|5L}S5pZHGMm0L?CD|McbpLo8?U8uGnqKkBJzu;7Jq#|@oHl5 z##MbTAtf}MJ9mSsT`-rpE~u6Egr^j;Gn}YA`AoNbesI?q?Hf=3tWbcE5@z!yG6UK2 z70h{ht2?i*`Y-CrSyU&TvckQ|)6xAs=Cip{@7t|F^qZnS;U?Jns_T`@WoGle{rOFV z*<~MAF=4B_ot$kWtF27}IhVu*Dc~}Fs$yo&!A-Bxrb55nGgo*9^a?riL!QvndxNMIUt14NttL2Va)LpjWVtVUnUX!o%%IB;;>Du}sHwq1TKKD-dr_`(zg_K}N)ii89= zcW?F0qmn!CIPN^VZMWA&md>&fn+HF$duhI)igI)mCUg6_72f@=uDJ_8?0knGSsP{6 zpZQ8SUs;d7^wh!iMvsYs>pA;qON;s|L3=?>9ql6q3W_^&4f+DX-dqJ#V{{I(7vZE! zr@v-rlro7GvF2RpkKe*CwGK9Eq^wxetiJSA`^qg_f~V`({mH(pzMLX_bNO*ww%4br zr0D4F)tF`7rK}kAA5((U%>BdCOW~Rk``pAYWi|7YEUlVute@CZulOQRf}NO&VX@rx z1K$wCExhNc!F)$~PhZ%=*&IvfJ)^JXZ&mO7%yTOcGkSAt{`@!LpTYzeA_p}BD2J9a z>Lr8(gMV;cz@EA-hR$4Xxfk@ziQxhkl>~Olk8sr=3$1thS_8w}h4AoC^Ci7`9Li^n z_C*puIQkR8T;r`#oZM5?cEMgJ%t*JrYOz;2`;x=fMMy`Pubr5uj2UzeC)E<>*(q|u zxq`87B`Cq#*4{>0kmF2qzl8=C`7u@{^Fne*qfR9YbC2yNHWr3cicXOr(+#}0mfHj` zPyLh#_$n~a%n;%hf)(Nu5_Rfh6+7ns0DX8JI%bDC^L_gk59Vsm$(DumUHt^T({ThJ zt2ei#)$rVaK^q9_KR;$9z%f>&P6jV2DtS@i9Gy7Yi02Sc8X^U3MY&`oNp6+N+b z`>F0*-HXXw|1frS%2n7==!a2%(Ao(Bb4G5vyt$NX zqrRHFEtX9xZV2KV2bc6)&N;H5vte!opUkWl-(6vCh3|VWJA3|+*msf*KBKubKkBt9 zVZhvBW;7nW**yEKD|b)M@zN(=SreU9tUdU?dd<1rg>i!<&V<{S!>t{%yu)6zIJEO7 zIz^rQc7Cey&VXg)YKC1TNt9(j`p>%-p4sxA_ip%KXvU3`pfR;1#P&Y9PCJ$tbvkM! z?dsCf=`Wl`t#HS8W8$k6Z!jJ@sde6P$k@I=otoiakY?0ACiVRdTz0+PZ>F8J?=#wu z3j)CbRm$CW8s1@VF5EY3QvP^ZTnQ`4czNart z1zrsNC^SSmDeqaVVVpDD9M(0pTQ>2^Gx3J#mhG0SXUg3zLUXfaE2$R8=Hl63No`3^ zXJoXV*PL@zd?s`H*QgWu%&1R*(5JH(-))Xm`Ja*veKDdNIq8#0bZTZzxZ6?s%W9HY zZ_8OSOMfqZ{d>QjJVb9+u4tmDGP(D{U`-sG{{2RW?5-!;;BA`fYjr9Neufgv#{7>5 ziHlgwh#d_2Q=isW2+~+r7rvc*Udkb=pxB3_7aX!0!IIAi*M9K&%Ss57rTOD<{gaFi zvv*^Ar#62)*Hr(d_v4l6r)8xl4X{`xcfAGE)OYSTO`q@xM!D}sc14b{(M_J}Ct~b( zZ#8^MuzxBTM@|)w=oOduji=QNyw6N^^0l;?Xtds(tI%@p@2jzuZ=|)?$|wzZk;#pMII;gC_$h#k5n;{*R{dqQ6 zoZ%RC{To6^JG)f6F;e#3LP_G4k?>|gpUr|sKzb&4_!L|PKRl&WzF zcddq*zkJhvDNoLHN}!VY_1pMB1ut6b^wQmSI{LJJCvSSqz4oDu9iDaV`G$@lc$LaJ z+TblXo}6SaZotKkjvstnDPETJgU-_J?>FT)LuI#o+;1#etgEI*jY_1_i#G=EdKPNG zyh(+fWDKdKzWjD-_-+0MR{c@RN-XOBLl zY(1pos*z3Slhonix7|rr5$38&_nJTI>oksNTwf|S*3xzRP;{DQni6fF`vZXpGwHX) z2ScX^N+&xr2HlFe>X*P=pt%E|Sz-#tT z_q&rHo7b$G&a>KlF1V6z9=j`tDNiY~z4E=O&aC)*`j+TAhWiW07c}eR@2VfuZ%>qd zk50Ij^3e=agl3DH*xac$OQNTfE89WguB>Hn0Wm=bS+=@DClL)OqB2WJN{ZtZdO*oL z@M!AmlAs5(AdgVW=@=&YcL`)a=Oo2^CI~jYcOR_RQAMUk5bif+6j=VqdfpagaWY{_ z>_E2Sr=0!Ajp7E+UlR|T#cHy@&R}zRG>mJKU`O42b%NxncoA#o4Zb9ILVS~Vgi%>Z zZW`)O$jA~IdLw`42-H{(JpZpk<>Y8===kU9;(J|qHWIj&b9{K^})zWVg zGy{sQ@~1mk50n!2o~#+znf4Z@$vD>U{ft7l^$WWgjxI#sz?MnUcR`&0v2$cD1s!8@ z`>)xJmv8S@5ZMqjTV^R2$X6d^mihQ6q&>`Hkx#x7;=%0QozPrZVM=qc^C#yWBO3Oy zgh5q9Ls`88H|H+p2(jUfPvcrqRuq@#7`F>BL`G(Ow1uhkCt*M7mA-5fKE!z~!l3c8 z-!zb3?OS(j40&RJVtY@&`q_8XkC^aqY;bxm4=vU^Uv_R^?wWc}xr@F2@U!0v2Din* zgjmt;$3PbsR&vMs=IILogBqfaJ?z;Zzc)EY_Jbq4C+5#SQt?E@dSEygUPMt8Dt4ED z{oBeJZKWg=o98%FsXQl=>Q7!z?&WG#v-UG}Au*%0=$)#ld^D-1b>*>!oxJ;AW34PqXHGWsR=<@#5T#?WI%ljiEw|BW!7&X}q zoE+d1OYJKIJDL$s$=Bf+H``AnEhQHP;36a9xfZ z@pi2d*$dxMT;Fsw8rrx~m+w9qT-;nzsGjKIw*N(_fu!0|*X_;gdnuvQzSnNfQi<9= zy>d2xfiC-d{Zz?^&)Xggl9lfh6P_sbZZ+&^b9NZ{)0$d0l{H=2CMWvE*}R~CFz&vV z-qU((yXkBrFJ)dmtx_gQgyxs>q_&`tti&s;zh1vhvZ$2K)X{7Z&SSkR&A5tw>A-fq z#6C~!4VAL}wa;13kA6jk?wk}#@ohf)X8rsX{-#YV0&R37dN(`Ncmgap&ggzM6-4X?umxy9A43wlK}@6>)cEWj!Unv0JOUJp+c|sPW$LkiD(gC)Z825cyC;^p_owqGw$_35N~Z)EJg_jMU2&TLp!+$&E3r} z6#ADh$sQ=R*-?F)py3-Mxg>a=>zTq01^Ab|ZcQG6sh*B)`3l|8ZzreUl~wNh*P zXwkv(0XtA_t=Kd4PH}PJk z$_yem@7wA=?%uFe)sv(kc~U*K9pPzLreplW>cyp#^o^>GzuG2oN98+Ijl84DMO|iJ zD04ap*KM<}=g#ggtvFZAg+{bkV{@@q(eUdHbCsn;$`sRF!@hN|vuHG=;}Llm2UcrQ zLY$ptreyR5p}Hb_@?j&_I~r68YWHM}cA5lpHpAK)NKO`w+?C`kR;6U!6t2_qmtmpu z+J2wFqu*70(I%Pd>Z8aT&Y>aXQd}3ZBnvUVS|sm<%|2w%tMx0T6JyW!P0wyG8@YpN zT(IN&0axsL`-$p^7gx5=T~opwwm6;ADJ!eWydjmc6=O;uR?ek1znJi~w-xSxQsd&A zHu%Dej+NDewO##mww+JQMFT&>&P08G9^kflZ`Yxh-J_1bl%eL5z?JcU+nz=vsKzndl7i1J({04LH;tPu1c2x3uYG5REp z);7A`@?R*()$h<_H2Vd99@14Zn4#Jqda%>f@*>LL>A+0O@#X_Dqw$_^RKBs-e|G&) z+FMj|E`3Uf<3*!MEz>CW6C*f-@a6gSFxfG$Ft#;AT4kG&%j>zyN!^~VtAZ)@>1>oj zd|~f0@YRY$BO5PuGdP#3(J){}PR3qNTe<4vxzntwrj;~P@JT>_#U|#1!h=~UxddHi zDeB8+%i`-%J7aCS&pa(u#h3g&W}_dE&et+)3$AY$M7NRab8{7MZAnT9e;U2~y!v9` ziF(RUE!iu;OOkr`u+lY^*m0GPL%aFsE6+w{GyD$Agp#iWFH$dw6yKlNt@TO1UXPz+ zVOm8SbG@MNEDcQ0QB7}O^(?vMu)2ZZ<(Y32D%VWQzom5007A z@$)65{PmeqMc9$#ktBD&@q1N*o%5D^5xsu3k3`0|gwe#dUiUWdmk`9hV)^OM-PSYR z^ulnG$D1Hf?11}#oJL)TWetZhC57u7y@@FU&&!1x{~gu5}LfLjUE= zj+bo&9XQJ3w6E>r>5sX^2w+^IUirNLLJIkbH< z)WKEQBf{Mb3mEq3qhk0~m+jI|SGo7~N}sPTv-|GQT$!uuu;Jl5ecsTP?}@$f@BsUP z+}qT680#713p~>gN=xI5^}Ys|KC`VK@M#!rxNe-@TwrRVD?cA)t9O0SOMCbI&xY%~ ziSEAI&&sy+Z_dRib$#_nUyN@U^hwbN2_MJ!2EE(ejm0U`D&Mi{3Z;!kD=NkZ$16y3 z9gNw_taL}0q{qq~>>JAJ{7;_ml|3_p&q`EJv>ZZWC8NQgeYb(gTnF8-n`ody%U*z` zJ(`f)gv6XW=cL|+ISOtp6H-xDlk@LmGtowEo%#KJFYIyXL~+DLqwAsLzKd0$K9Avk zrqn2EX6?)99V|QX(+e?J?vF-OR}08`1Du2Qa@r`6r>Lr980c!pdYy^8cKL@Ke)$%#;G#8r6ho6!EBN2F{YDC=C3^93_i%)=4(!@#5 z!rIab3?}B{;)0s_B7VlsEyxX#>MUKU1^EzcJqd_B$<7O!YlENhP{R;^aPa|lBE;pB zF|oI{^JY?YvT&f*FmZ4NEO_W$YdZ^WYGmaH^jgKl-hxv?Sy5bGmKFLa^htIJM>}(Q zHxoN+GsM5q0E9g^Gb>INM;Ch&JH%Vs$S(-Ux17iiiaS`^Sx~cs$+sGA7WUVv!N_9{ zetvEwH4*}X#Bi~8a&vUy)Hx#FKMcYnWNyGD7U zZs>b#$E?MAFVFUolwY!9IiH6vy!sTwckcED-zSe;-=_W;o-PSq*Lhs?QFqiwtxr@_ zU5bFXj6&ygcm~Z7Q)H-zJ`Nq-sq7RNp(m^~xo!Q1T4p)rov!PT$8$1M-iwqywjvXz z)Rqh!RNf2V|4FsfRaC9u^}(y)_PJ_xq7ht{994IT!qp|=+?|~nTq)+sEaOdW>#>#| z?AnpfRKRWNatnH67MSi;l8vjtbkhabJO`J~LduRimsk*2T%L&g5_4{L9`2Vxoze8b zZ?`P{r52+!-3%mVI8}dr>~0>XrdAxI+Q1NRcbaH>Dx#1Tdb2m~{*%uo-b)vh#%-v} zPbhM&UA~x4#3X3Ha$i;>;EI!d%vXanu0$rfS@#wK(qGdV8^=Eui7Hg@U@zG+08C_ zC)GgXi^n{E)s3o>IgOo8YgKpCZDs1G#7w#7SO-o1lIq2MX%o-RQ-)Npec*}>xOPWV zM6)V`g#Bi#e5xvj)qWx#r4QYzY!Esc=6BfO|1fcg_Q8iLe#jX|cEJUl28iAb>;&>J z1lgM!*>9d2*$SK**{vKfo)I5GcI^hNXXGm+^&HtcnHt#xo*LOKm>Suo7_g0zpG4G^ zP$S#EQX_k+QX|`uQu7=V*pc4_*(Hk_Nj#@Uc4nhSwn?K#c8>%caK!IK_AsPIwyvW_ z_9di7HteHDc6g&kHeaJg_HzUTa^$~5eitO?ni|=oiWqDFLKx<-v0 zwo3gMtsY?*5ytz7VLY5B|9@f_4{HGbWEm0rcetg$Gv<*sPGH_WHyp+X4TC^X=s_1) z4mdR*FL)mCQFC(%aDXyMK0ZDUK|U0y>j*9R0~n(4g^L#|yF-8hT09@1?1MRLPyr(! z9AfXI0&|2S|G#8H!XWDBj>^OZ$^rl*pP!opY&wK12uB6%2v`0;z+i_ZE=Rz41$iMb zZkQkk&^Ivi7DcclY@`1I<3U#P90d~qy9G%G+9JWJ!H8NE!H#$|{|Sby$~p?h4}-wq zkVw>EKp~1)NBxE03OD{Pwfn0i3W)^+ng_H(5V4A&paYyKFn|C>up{oke+!1Fbvr5; zR5k)uk&g$`4_>Hn1Qq=_Iv(IZ!H{*0N5Oay`T;86IY7lVFC0bvI65`p4`5Km;?ZT~ zM(77OH$Mk3aNzi%DA|z$o&N?y6gV9P19dKt<^yE}XPTEAMFlz9|NjqQPz~1+FyOf% z_Dm3%F<_Zd)DOh-=g(&9uL{hgSON(B;O2pIfPs6wT&U{D@%DoYvWaA+N4CmtpqM=|D5zp#BEZ`vwGy?0W zOx$3zpmHUCaI_&XBL0Rtnr zp~y1N3S^ z5$s59=6{1B=CB?G699)9fB{V4rh)E2D1sehIgZRDKC)*#d`SHOC3C=+O zkJ~fkY~iDl0WE|i1I7?MGkN$?R1k#Ic{~`@^7AMd9HAh97!3R<;IX2rAjg=F!)1iV zbRS(t9)yB$1Dyxfo(GPqf}mnLkVCeQN(K%Xbk4vsf|5&M8d1~yV?2*T!JuOFqgY&r z`T>W0Q_%boMX+OB4+!jVhW8OLZb5{8@PJhWRir#HRQ2N+*8?FLa&rBVE#nqAG$4E& zU@i|gH~=UulSmOd}8s zcsr;GhKl{*JMzp#m|<@Cp?>f|MZnzPVTKymk=oxs2nJ13J}MXw@&N;M5?lqjc~R64 z#C7vH`vLlR{(Yp8k^wgWVe^5pf({$1`f-f?fF@P)0Ig~gHwzO)G;0hLMj+ye(%u*1UF`| zfZ(bE71E%l6^K~Oaq9<={-qUAJODf&5eg53!U3oVb&Rn%6bc%ca6~957y!-_54bVI zpnEeaK*z*54uPP~8b^SjKmY&&g26%B0W}~Lj0Etnp%IQpfS@1%IJLYSp#Lls13*Qh zBMt`CV?l~j7HmFfpv=oD176B7Nm`jWfmQ_KP9U*iZtbN3IyzW8Iv6{7ayXgaWIoJI zfP{#vlZ6?lmJHMW0qE@o^>u+dfj}Km#KHeTy>F1+ioHPh+M~TOjKR-5(Kx`L=4dye zjtv@|vW}XLU{(m!8A2QZ_P^UofEyU-J_Ma;=$6C}t})!G*hNHi?ociNzh@;tiwAIx zMz;JpuB*clll9*j3T`eQzN6J?IXe24Db*wan`M1;Zk^{03Fn+=U9MQCF!XrjKYo>p zZEAk!EFQ;1qvgSF>1CY7sOc8b$KB>;^f`{>P43%2@_iLH#^*oYT%Wp0hjTe)TtQml z0onc|Y>vBfbR4ESLQiNZS&5w!h7U&eSniq0@Qr@FNOi5k+rS@x-zRr{XDXjS>IKYO zWBJWy{jP%O-ks-;_cU@}Q9X8erJ7&SHh2g>F*zQyq_ASCxm?785T(wSIFuy_gi?=h{Gm*w?XNSK%7kjo5_x%-3cBDqY zW!Vh_{O8t7)uq-Qrm>UQr+iyDyFCN>?6ri0jbr^9K6Z(g)%f6_c=<3qlD&;<@o^AW z*dE0g74OAZtWiR@b8!tWw%r#>#b;ZetACK|Ffc;HiNn4<%6p6J;w_d1gYWAbwnq9j z3b&urPU>Mvr-&u2Q=-GrI?yg#d*mDx_53t0!;@j54Ohq~>Suo@YpOP?+M8(~m`D@0 zLO7j?7kPH_BTL`vTQ<6cJh$i343?~YL)j~JHL{F zBS>8$v~qty=E5V{PTG@wGUnedbI-dH)-q4O>bO!)Q8GmxAmv3o5&L$Y3wPq=ueZhC zV)ALXvs^RA_HpveJHF1%MO8O_A!NQCelo|wr?JC(D$cn%FNriRHHk3OoGy`GMZJga z>%C<+;p?h7Pix@{3=~wQ`b_ypzCCy1U5% zNf062ldW~OuVT)7;?B!68@ETAT<=^Z!SiVtWN#2K@{S8hG<8oF`kGCFcp`W|-}$nPz^@bdThS*&&?TBuJ*tz29!Z!D5w_{J zJTRBHi2wA3vH8on>~H7$X>d9gBhT4e#pamR?BPFTApkA;m8|!LRX0LX0`|-uj5KGT!WtJJJKE|r68e0v_$oM4_AG#;5VCllIRPN7>$VfQ`c!;^iS zU`74fVk*Axdi!#zl%m|Ltoix%Y}8Zwu!*uKrd}v&IvJ66qA!a!(NTrP32>re&`PT@#= zE{or>aoQ#>!$|~ln_oGS^l{DIx_jnkeUig;ELHqj*VOJ~NSW+lU1U?J9BOa8>YSDq zeP1wLu=Inzp{NyG^;)pc&h;kKesa8Tyl*Tp1{oZT+yydhIqRt|E()A|gI>G$`O@1l zZ9S?)Lr%wt-kZgSMM2~pQ8t^UUM-nw;x2PchL^VN^rnk_t+Cv{PrtOSVo#J5@(SX( z@SaQ!r^>N`khRYx(8g7RaFgcwic;` zw$aD8)bDSox(LO zAD8xL>J6XX*zLiz)f)J`D3sM8dhjKAqGH#_$yb@cuhbR4?r}T|Pc9dE_t;n(%y{#u z98X%^1HfT1-!fn`Mrl z7kc^0;rhWTF0|J$TuP1@fyev zBL6~WO_4qBfyab+6WOhu8rd=(_)f?-kr`azq(c83*({qH+2NZS*>IW~+1nbl9z%Qt z+3}cK0Qp^zJ%Xu`jh})0iTnuiyCA!^QX_lFQiIGQgn(?{33cIuULiY(QX~3qf>+4z zg6yzJjcmdOd}rh*krE+WYEdIuA`s07@k1E0DJOW16bgoH4hdc(zYvTI`Hg^+d-!?e zZv!`g!`BGe5S`d~k@@E%X=2#nDBu5+JTbWYK#-h&N)#U*vhtrdLmqG?`|BQn$WwsE z2hd#u3X=i%m>-JCq2d}JoviW)FlgT1kxK_36q5rXE0CH4S3Z6yCWjK(G0`N%Rf-4p zPX-2Yy$0=>k*OsRvjxfwZfz)Gp>#jwg_^n}1w*FWp^zL93|z3G)HD>5LkSF0v}5nR zywL2(qpJvo&GX3;Zkk0y-fhz<@3SEGQy}(kdRgq5Utxpvlaj`7zWP z6tQE#V(~%|Ib?ng^kPIUKZmfrf7mR<0BATDG@$E<7V<(7IS`8jDgp8@5H3pb)1z}m z{!1o7YB- z$Yn&#O+G3a#H9paz=}Y5Vkj_&64)`8<1es(Nd`scK!Ouk4rtGy&>Tu&$5;*o7!P6& z_fg59*c^}yJ917BbV+O)zz*T}nVLFrqL&06oCb(I^dM@z)(~V#4Y%^RRqWAZ|?(Pgt-Cl4$?))mjk*8-a~B_ zkMTaBdCA}uK~t#_PZzMo+<-F!#v6xQYMJ2gGhdZ z-~j}SN^T1gFE}0wn&ystULv6&rVfAt&t{~(M+xc}t8pk5G!FMD6vWd(NCiSS5QPyX zsAFu#Ur>L$90+aahC%{|8C-5CAb>({5D{8Ae*ONHR)sH;fI_ysH;0_SjXhR4_ELXx(7lpU{E*!;o3l%edwN!!V)6GP{+&lPih~r zTQDdZ0OUIK+)z^tWT@+SENHs@5&sYdMFW8LfmVQH4C@tYJzQ*Bp{mbozL7@N;yy1m{H^6YAh;@vsaftP=;0-X0kXS$`AiE2m zUZ}~1n$7r!;)GN~E`(};n-?J8gBi~#VxeR-c>l4wi0u+UY6h@`018}YQ4{MJKLfdh zy#L~i1Ku0hEhO0=T#HabI$Hbp|4S+#8U8)g`ak6IdAMOmbNSD86P8nR{O)sJ7iMb}E)MO;W*=(YE~h8)e}Zm`6B#WV{pE!yOQj98OH zz}C{;SS{aG>wr}g(cV*ZtFz>n79#0aEU{_nxT8arZaDa!jgWe%<21d`Tbv>wFYt)d z;ikaLSHIS0$oDoG&2ADzZ%Q%Z)Uj(%KeitH`h)6gsnIfjn4i6}WWZ>m;@O^B6;~3T zWSN6U2WQot?$FW{r?6euO?%KC_}1|UJa0vSEc~2mcKX6nwcTh%>1!Klk6n+w!KQ_I ztNqP0Q)mWqgeR+MTRaQo=QFOqV~gOu97@F|Pt;@1W<}mw!JRB~U3?b``$E11htd9 zCwOA#HSal63#O&2$53UW&kPXQa4PHSs_CX$IPve*rLJH6y0J)CqSet}%Opjaue-q^ z8Nh~t`?BThBRnRF0b|U$cB782frUn+xD11z*a6DSOxi77>=!;d;A4;suoFzYhhb!2 zYW%%D&NYZ+vpPqr}uemHLsml;N74VGWg znO7^JMKgXOF+2Ro;wxp~%w%9KHfwIqGntaPfp1>e4%icXog92Gz#bZ@5GL2OlSoqD6Lejb zM50e$f`b_3aa9FQYW;k*MMe=f&(#F~%I>h&qWkl9rQ96?QH=jM%>Z$929^i30{jLsc3g4IdGeB35joS@5LBVrKuKo zy7XZ`@#5`kDkokX(=^*V5FE{TTaB}lzjI+wukEBlTho@ww<@_Gp77_ZD?X0 z{WUh_9)eE_i+w&nxbwdC$;%I&U*45>hfsbE^EA%bW6w13Y<~LvomE(nvAK0XC?U)B zIu&div56boYDv#YXI4i|r*bd|*57|scpCBEZ=vVyc#NkrXNuG?!&j%bb!i-zRG)l1 zW2ZowW7hSJGgn2XdyMo-^>%3#g>i`jm;Fbg&Acbine%VFyuY2Jajrv)O~a!#OiNBYp#7?( zKSP4(S+Pbfrsr4}JLg8o(Z(1g;;$#*X|7a#UZPkpOu={Mxfd$Ynw)DK5#9Lk=5;+o(^Bg8YNp1|Pt5uYChKqECvQG-mU~*m=pcrELic1aCc&L6JC;98 z<+L3#OUZCmuZCS9`#9vyqJmX7q2oX$41UB;|_|RIuKj%)7IjF56XV4bSR56v5Ncd7|fhbK%?2&Y%G^HjXskYdldnH?O zR&h$XZHsMJI=*g}IVs*mMuWUn%&)3xG4+&P{l<^C zyqqC8x!RX_%8dO9@wp=YQ}3K&iAWsO?sD86ZW&^GV%ad;G=o+I3oVtLEKVZPZrLEm zda9MtmZrmaf>&K9lVaFs%e>hkW^aAcl;@7g88?z>&q)hy_=|yz-YAS%=d4Pnz64=| z@{uz%hHIFn&p4AWGZ04#F2!A$Zai`D>RrHacvRq6y3T6%xt^J*=Oi~clADr-11wi1 zslplct~lYFn|$~f*L5$SHmRnZUtOeu_HwpwH>SWj(X-lT?`@;q!J9%;aiT0Tc=(c~ zWR~EjS;nGw4Rsg8X+`wUQP!HuF=<*pQOUo;ZYASy^!OF-_n(jYK-?7>OsXSL5Oje` za-d9UQ;(lh<8%$zRU-Ii=JKb)nwstCHo{*pyfgo-g#{{~rFZ=6dtv zGNOC;*XZ6X29gOi7LMMpatzp|O-|s+xcbtf*5P5RQRw{(s=@B$9!&SNrgOy8?^u0} zOrZ(HKI_Q%^nC2&VOac>J$9P-gS9=I(Q{{;;^y9%4yJV)uzaH{NY+@?Y#7`5RJO7H z)!R5&@lr%~HRksQ;x7e)boQ$RBJCSZk6+2oNpenycu=oa33**;rQJ!*r&`1-X7Uf| z(GK-&lrMQzNkuZ=^esY6&Y|R69<>N8#qY$m2AY2F7Yhm>(r7Y&pk3@U-@Iso_QX(Q z{l(2@N!yPkUAUib8%i-Rwr*c~Vo_zw`0b)Gr_um#zgp^(!D;#J3rVg zCO1=L3vYbdO01BJgg;X;ufz0-U1%M`dB44xu7BV%(7U{}7^m5y@;UCl4en^`+&$8Z zD~+-r6=s&W6Ty8W;6b{KRIxCVS)$VZ3%hWuyfZ^*ZW{zhc( zf&YET1URg62UDq$KR>K<2bI-_uMdCUVW~Upu+|;a4Ilpe@b?{-yTcCa-9fS)`Ex{x z6Tm$zc?WewhwmSLzr(6`aQ8TT|M2%67QVv{E8k&=8Ug&?!|Hd~Vfj1k zu>Kte;?D?q4=dooJqr2yum&D>SOgDJmWS^j%6nJ`4@l{U?;oxoh~9wTcgT1^eD)~g z0ZBOF{J&v59F9}|6XOBgrNGxY_GZZoO$9!3i~Wo803wJys52hG{Rt(ozk^=LYwRKA zfd^SYhBD;=WRX!r`~A{<$aw%Wt2uz`qfB~0o|8W;Bq-^KKSGouU^!Px0_ph`z z$P}Sec8WZQDB%3PVTgMyA2P5EX*Gn3Qiu|H)Q^D@go7fqzjOl$g$yghK`R>W%2`vWTAov|C<50}gdjKv_$UiH9L&1IdQpSMo4O3Q{YO zY^c&7kWcwz_YE;x{Yb=~7s-Ess)hg;5@r4aXe)-wO7g*fH(Y-aAOISoxdDnfD%f!~ z?BGEHcITfWFJSqhE(3?D95}F(FjNAw2#4qoOLzza``z%vp?EXsVgur{fT9ZFqS(de zn9SQD+CR1*5yFH+5odq~I2ORK10|fOq8;Of9HR06o@IeUL1&P2137iz(ZZpqGb)`M zkS^r0D+yxsf2lrFHb@IWWER;Q1rEiXQA0b%h#+MH?1SIYpujVf`2ekmK=K}nJfnto zj1fVift2}gXn+%eKm+VIkQ;-TR4AeyV?-b{K^{SY-*u7)3O_@gl>i9>)RjX4Xw+nb zT<2r<4Y2I~mEGatLud(CH+xH@*El7Qp&my#f!YmiHf*ftnsN}!@q6wy#JC4f=% zI~r8M2^}{?!ybrSjUpOKriAyObR*($^FZxO02*lW0rGMXZxKbbV{SCamE`~D03gsn z+e?st0Yq{H7}UN5CH+TSQIFGq&;jW0vyIp`h>`=d1?>ohdL77x= ziw8@HA|nF$?5Kz(@XzBDxm^fK1RyE^Uj#+HIIgB0A(Q|}I{&tQNJa#diUzkPlo=6- z@Xc{&O8_*A_#F$$hyX4)u!tx#A`qPtkHZoafc;K1I%GtEq%AmGC^I4uVW>Z2adUC; z!2f3RAvWuf5dnNh;H5%jc+`~e7~cc1Q$P%a2mZG;1fDRs8T{4z5QN%L?0tB&s{DUZ z&;X$m0{W-w0{}r}Fk}e<_z{Y+7DTM>4~zFV&hJ|BSHmcNh<6DYTvWKLu%qQ?|NrFI zkCr?AcYYnXpubIWjnjSOGF5wie1Y{TCTZ3Wth%JouCz3P_%vrbcNS(<5{lCgF6hTe zTw7Xh?tO8aTe_8|q5gFV_SIBh=jA#A!@V83ch!c!p6eNuTtBT|HNy52t{vVYwi(Py z@AmrSt?wQYaSthSQ!VyYD-Cl(xT;u46?Y}FKaPIEIaswcOV}i6&Q2wC)3-0~&GVNb zNbj57+u5?|OC0!rc>4w*%eFSlG%H+JLGZ>_!7W;|TbuVWsH*^`@z(~Ey~zf%tLbNvcpiK;qGb|6~J zD6f_?SH=}_JY(C9+hF#ic}-DMd2YpkOfEv!H`38i8(IU!GI+h@9G%;v_`#Y9ak2iN?b8p)3fm&nAHy9aLTTAR?g4ElnxWMr9Q2>jQ(vS7z^^x8f7f4{J zYfkZ=;^{PKRwP{6a^*#hmmpC9kmBIHAtG0)RmSwIZD*coERd9lkA~L{uC|pSSd_uW z+b4I;be86>+*_vc^d)xQg0DlmeS-~zikN93^NQ-{9Vz=SicJ+PbN7p1HR~!0qh->? zQas_$$bo)s*hGe#TwIFizfsz{ex8r~@}=IK`WjmKgmh(X8f_(!yA5DlWQI37yX0Kr z^VB7DmY;yZPvB`$T@WV|x;BZ^muqtuMNCqM%cfwLGfi8Kl;fvUw(~08{tepL9mLF# zuWS;{sfBU|7N=Io(8ZOEW+YhVu)M4xms|mkY^D|&h-8bCD#$w?D$IIH^Ux``Ic{zI zhLcBcfY%s(dPCx(qFQE2%_g`K?{u5T?%I5-*^=_78Yc4L z%l>3#2|E!;_a&4@&zboOVJ?n&4yzw2hN$lo(sUJWN$abEd|z2<58)msk-37q3BcKS zdGL?LBY6;m-J83!$OCH$ya8+$ZP1x;Dk16)9SLX~QI5ZPfY;@B;&3Zeqj+@#V((Hs z)(eZ1My`U(;Pc@VOn(vkwg{X6xP_>$!O0;|Bnl}y!?9>@>e0O!g7`Y=w$V6<(C9-# zyV^3yeoE5oF!!rA%da;5a(rXB-IXG z!Q5Df8oV_)qlRGW;U_3P4gHHs^eYK@ll@0HyiXb}AbmIZC1uNn^%V1<_#EA4Z9@_j zMs3JNx5PA#)9MW(h`nnw7a&tM+w(Bkg(JaGZk*%-YaWWU?tl>DgbGM(JaFz?CO#0n z>I8%+t@i`hF~WA5zJ0CTW&!r_J}D@fU)Kw_&?~T;3JJ9C(-;1|;xudj^bm+-%`Zrg zs=a)9Zx1HRR>E6DAlN7wDFcoJ)M0yI?vA<;HzN%_=88&A7;(CcCT-7EzBDo4-T=3+ z`4YwY$AY5bzMxg@ttYus-8tNodN15X*+1j5x!#NKNt>}daywD3xN z*ko1J>8%K4)IA^3v(r_B`m`I5q-qBA_Ht}^MzgJ4Y$Ze`bl9fBdOwaRuBH*kkaFF> z5hmCDEL9FCWm-M;6gO;bYwk-Iat$pXt_|A_bdpQjwp*O-&`}WZls7bRg=3OWc1s=A zDkHO_vgK+??Zyd@jXEV1i^Dp31~ez z{}2ge)ycc1P}Q$v4yBT8x7w&GkD=^?fvXshgH0k?An+dpRnV> z%reJ{72mUnCw$H<7Jq8L{~G{7Y5+c{s)&rSm_PRe#b9 z|D-P&KSB9_%TfMn++V`#Pxq=nlHh+Ttfu>Or~P-W`*iL7U(yujzopfmxXmXK^^djH zf8Egkpt%1DO8wQk-}v_L?fic>RR3dj^`|Y}Kj_TQ*3tjRB@q^Sm3f?xf!Ow+;9qFYtwg5AFq%QZvz(Cs#2(^1y zkWVq9B&j6lc~(TWA}UUt+SB9(jFATs};mo6RHy=5r5dXm^w$`8k(Y?3uIX1vvbqi47yYz zMoSDgYfLg$QWkdu5N4vrqGN;VU6Q=uIxz-)Tu5AHb0q&z`cd#@3nj0B%&0|ESu+^? z*DrrA@ydZK-q{}gGna*cPNJQk939p%Y}vC2%R<}s{5%PXUi<=1rKhi+Q$g;;9 z0)d6qC?d0)1m>%K)vyoL4|@1Kg7leI)w^{u(AEQ!3x;+Y`NkXRq|sZcW3++30O-GK zwESmro#kI3=zojrpVR739RJ(sh3*q<{`~xRoc<0Z^7MfyzL*>@n1l&|Cc@a8$0_9wV(C-9gKdXbiXV6PayC= z?m~a}qQK`U+R5AK>KlFzx`6%XX%>I>2FiVo-amPee;zpSNtORzQYt8X>O(#iEq{Ob zL@1g5+9CJ(%fFv4_22n8(tNl4yp06@x_sB9QIXa&`*gtktlD?W->f*6Ul(^q zP6h`LX@`IS0O})N@!r$%(|Yvi9MEMYf}*%g4G2v_+FAPHXvY6wV-2J3+_+-D=HSLP zCp@LXs4014hU5(-(D6~3psdC1Va-IE^!K8esDz^ zmL2f-5bQhWW2B4l%h4qEJ$3hnqKc4*deYp9@WF51ta@vgo5f5rObrd^m7^;YtDAJh z?R>*<55%RJUZiU-)U;nkQ=i$G;>~ddKcb&2)4%j?iUqVd%Fu#w*lPTF9-qF*S}x)z zsv*A|obEq1THB`1UXDK{5SFY}q-bqu)o}lvrP9q`F=w|$Q{Hna0uIA{%jGF~QR^qX zi)00sR?xoHB_-^o#Rc^##@nTY?Q2sU{vg6A>?>&vAdXb>rzK`p1X4BXDyct}`@(lT zLyomXsen0lEvu*#6=hDq`j^YfFV?$-10Pr)n!`YIBRvJy>1ft^KxZMW(IP=_SAz%Z zbi(eG{P=E<$cpx8)qH>ictdi60ZH4^1!(4C6Vv$A0V%{!gwxtiiU&z?ihJNCL*^n8K(1wf%9O%>LqJLCXYl{u`doiJu%Lv;Uh?T*zk`q8gou~=|J z89I*v#^qP6^zbgX-AJ>&T)&E;3DP3N4@0{Ii&H{a5x3ettCN^EfHN>D+~ua>Z0z<@ z(wv`2&N-uFR1pQwWy3@A$zUbZHw_!!iWG=RL-$K-KkiTwJ8D?Qw)s5mR=;XNkX9!+ zcAs_AzR)#;6%%21yv3x>3CzZR-bV{m^IWT(bfKn;bYRB0)r|nPTn4O zD>O|c27-lLRUS*BO8WttvF}Hq!6YbgO6-d(ttUZmiuR+o&P0i?M#VlIpX(dt{cLKz zd@4}8@EFF1@Y7FtXiu8anO)XimBu>n>R38saitVvpCL4IFGAJtVEDXpZ(nr4MNY;0 zv4FDUk&clQ{OE7ZTChvhMuC97=_Z7z;@&Rk6)l4`ZLBFHLO}N`H$qXMcv@$Enqw;W zU>7O}fi6?!v1~JdQ0j%wVb2Uu+of>Z?4wo94+^dPVg&`9gC#m+rH(Ml=X6|S7O2X) z5{3SnnsG)nc`dtsq0T>j;dFS5v8ywt=Q$N+_vKb(2(;DD`?o=iD>gKY>uF6VbsSQ8S^dtlZGB>2h5(f;y9>8EJ-Z^R*NcJl}- z@BEdWozg`Os^`9@B`TD|XEKb?z8bW_r*tS_u<&@)F^3_55?2-ksrc6A-}7a(OH0oZ z>NUx~Enrjv@D_`!s9E&aQHt|{-qsxY+z{5$Hmw=m$#xVPMBJUl1DuP9*yYFNsVr?s z{iy20RojbU!QYgO!L4?`t>L4-GTR7k2YExpqF$f`D(=V6J)X`EiB07jUX2$ptw~t+ zbOuiT(mp091GNCcI=j@a{F_C@7c!zr^dz z6ZHF7<<@w5w-i{KNV{~bJV(O-GQJ^4&M-1;0iyOylGA-7vrFgCR1ku=1r9MBm%u-e z2}xRkiqChGVZ~Au1R`jQ<9MlV{nojU(Q=*)-9MLG(;h*N@)+pA0M!?}g_@f7asV$- zW1k#3OhOEcnR#4+B9%a7Ml3qdE+c*B#vw>J>KO8<-MA1Y;SpEZrK`TNk-?6v>UOHY z5YJk?gIMbH1360XsIZIA%_G`NlMz(IwHioN-J`Y>6!eZVMy^R@=$&Q|QoZ<^JHHgq zSb`WTuD*E0NJjZ&8s!NA9MXMqN>gUX{@uwJN>B!3rMMTvGc=rN#=E2pe2J)h6)N>y zA$yW15Te?xg^W*+MKMa9-`QUa&uI)auVZ;&n7UJr`gMYj^1*GS^m0Jk5QLn}s0VyJrF?2k0_6VBK^=Y76z z!&yJJt5j$oL^?X}LN{KDBn?E8Q|55ffnN(ngpRi%c;omz=Xjzub$p`V`@!eV<;qbmAx*WV4C7^o|Dt#l&VsuXAky! z%x0g_a%W=bzfL9TT-&&8>++8``9m-Oh0;MG4Ou*6+{LCk9{1hzE;u;ojIZ@AUcV3!TTq*PubFehW2zo9)3D zEOmTScpxV-Nq=CPMzQH0y?3xSP0AdwLieKV*oL%toF>TZ3jqm#76=t`kmWb8jA&_d zBK}qDu4WeYl+n@rcpAqWYV~%u7@Y&ze5M+Eew#2`II@%!sH!KK1_W(n*};|UdwBlY z;GPr)+;-r`HvJuy`0Lv+T_d3!DQc5frw~xNuUj}Ye>W)H5l6710qUb_H#ngSA_IE8 zz%3E6&2mJnDs|nlQfm%4WM5BzRg>DVN;fKG_T2my6|E1WsypJskZ3QeE1oe6y{ViY zJT$?Zo*HA!Q}+07ey*6M#a&?G4J8MOws${DzBgNOPGQ?CF@z?h6Fyo{a9QQ|bB9CP z-TW-u!MZ+7zAfW0NNNZIq#+)5ie^s}6hu4cdypc_WzC9bNmZ*kKOiONoh5i7GXmaS z24T&l$c1j&w@k@I;J)1U>mNmvB4dXFnj(2y0NnH%G77oq&ZIQEi?VHBu$K|o?qg4e zkfP$oX_2Y$NlC;Ebs5+%A}SId0;02p+jbdnf~9CoQA!St*(>mI<`ToOF`~hDHL>>c zCQfpU8(r{@1$M1ULVki1;7)c2rOecnNBm4h@lwt?!pniY>f5#_?8VFJBeP@Kv(w~2 z7-)e$3woDr)ddI$L|)M#l5i29447t5JiH+EKLBndoWCm0E%r(IGN?2Ab0pYIU}F(DtjE1Rng?~9Z3cjFnC z>Q+yWksv#$F=X9oaWSUUL%qK^r<8fti_AlIgXG4+&rGFL21F!W?fitis;%%rtK)Me z?LxjrN9y|VCwv!bshwciYfM#o)*owOvRALP4`uFD_AT$SZ6W!>mBz3{+qjn-iD3re z2O3acz5$VQv|+P!On4JKGzaaCTW&fyTo+wS}B z3IsMMe9)^HGX2bgT^ggebYXW%;skNA7L21F?z1Z!l689ppiXuLKJ+2$#8fSrNRc?J0%+h*X?6{ zy!svAt+{s1Nf%RQIepkNGq<#;2kNTy1CZ<*T^*o$d`7gLigDwL2ZP~}x)OAvJk~U4 zYYtc(v)V0n=cQ|Yo8-cEssvd^wF zQc^-f!f)Tc5fc-Wk&%&;lT%PoP*G9Q(9lp*Q|IUBKRrE_mzP6BLjwQ+C@Lzxy}jMs z+-z-at*opZA0NNGykur(K0ZD^JUkp69L&wlb#!zT7Z>N|=7xud8yOj?s;auUxTL42 z*VNQBHa51kwM|V;9UUEYc6Q$1-(O!}&&Ix4J z&&|zkb8`~~1!a4CdtqTAFffpSfWX+;cw%DW_4QRrNl95*`Q+rp!NCCt2nZM$*v7_2 zM@Q#V|KR22wYRqi4-X$7A755h1_%fk6cqI7umA-G_2tVK2nYx;Ffe|8ep_2xP*Bi_ zh=`)1qW%5-#l^*;p`q5+R$pIVJv}`(HnvY3NI^kCLqkJfU*Fo=+Q7iT(b3V>)z!(# zDJdzbu&^*JEG!@(AUHTUCMG5&B}GL=#ogV#y1LrK!()1SdTD8Cd3kwlZSC^%va+($ z($aE#d>j%Ivb(z*9UUD61SB>#R!d9kGsRa^Qxg*tD<~*PO-(g4G@P8A%*e=CUthny zz4i0+LqbBr#l^L^x98&Gl9iRk$H&jk&X$mnxVyW<#>Upx)?Qs*ot>SHj*iaD%d@bs zXl`yMA|le%)Xd4rX>V`;Jf*y+r^m|5s;Q}|w6yfsuU}uke%000{rU6f=;)}7j7(x; zqPe+wR#uj$r)PhE|KQ-@?(S|&OG`;f$&VjD1O){X5)u#*5xcs&;^N}w=jZF{>eABE zA|oTCqN32y(8k8bHa0c}1_q?1rRC-2)z#H~e0)9;!>?~%(f`?``d9zI|9Vn=4i^(G zjfA04?A|8R)KsynocLf_K^2g5m7m#XvR3JV? zJYK}9fEP(3C_TlmltOeqcyfXzK1u;V!-#^w%NUkZ9cmyS>t)Elvg+>q9!jEb-i*fC zbXBdE@7>!Ep6sqUE>;iHS6=V!sTuta8$tkd7f6lpC^eF_iLeENMFjOUo-E!uz zyQq%ug5G#aCSRmSTM;a9%$OBUJni(P%knF@6XZVJmRcp%pFOXI3ht#x>vn|~BNbwC zxLyNHm8dgSS^gBsIJKqIxIWP)xswqa4G5bN#BvU%{8R;D(<`Jq1nb6SnFwMw=Y_!MzcTXXC zgp(aHJ!!Deu2KJe z^~*Ks0aayt7UZ5g{JNa;+K}@cmlPqI6p}rNDWc_Jl@lMm+^Qm|HXD%GKN*rR@RUzs^>M|cV?4x2T#O4MQAyjTg^5skY7Uo_7 zRj1#PH*Ju({Mp-$l12S71gn!O9H;hAR12+ypbIBG9g?&FaWAqrI<1z&uwXf_xt2@^JjC z6ZPYcivcGvO$;ga1t_Qu371Tm)64WuRDj)6+s0rrdMma*;PJ0wT$E1=Pxb-g;&?S> zDl+?LzJzyD9iB0nTrjiq(p1*}!W0(?TjzbZe&W^gIcRu=_m-waF0GAywv-e}eP6oG zRTZHgt!;|WRCI#7+1a-5EMrsdCjR9MB2-dqeL?A`v^&_Gq1y5 z=6I&{%xUjosyaF@P##6RQI?a425fJZ$I#?|qw_A%WgY|bu5&5R4|Jdi7)no~F*jj2 z<88?-Ks|JPrttJbz)JwhFwVJWOL7!nN_ROo^f|jmo*Vr&?-96qScapUGc-k#2bjv8= zywgHrai8O7}M_L(k5Wo^UOSPx@s1f6gi?HxE`duC|+bl8cpEzs|8 zF!mY^VhmTK#vBgXY6_3&W0UWO^L!{+F?om6)He_sO#iV0Xq>_3$Ozq8y8HLN} z(#|%%QU0}pJ0cyP`yRFwiJ{NprXeTfLwwY5=W&Ko)#VOQ52Fk(_H6Uwrs7FNOG-8O8w7BXr7NB={hHPOt95kYRX>3 z6Gj|(w$fG9w`46rW=j=hgBb?ihA_R0%vJFbn^d%F_~*KB*}Jemi0)HD3dDv8Px@D? z>An1-kfqUsvyIX6dOxNkBq}9Fu@5Rj%ln~JMp^_4koi+uhpUUY)_`3<9B1U^^iHgg zM(8GR;7u7*=#QY@5n(!)StASmta2%rqu3h5>7U%xOsI|I@g8XWUw3Cajby>Xd}}Sh z*HQSii7pKWyUk{wX$C(~@$bYJjUBjdbPbv0;3WHhO+w)(o8fsU?j-XocRJ&i(cK?c z$dQ?gm_uEEAtB#!t$LM79=9anlU0rAEWZGDw(P#r%t(%DkSj9Lg?w#azQ8?Y0rfM==-S>gV+N#` zJgKiCo`YX|C@HIfg)6P|WmcLma5c@@M#TlOXSJKL(XE)Y_*wFFu6qNovbSB##7e$> zVQ(b%a)Y?Z412qxhK0CvSkfVB!^k947kWPObC{V&wiOe8S!zcktLF0?5&|t9W!AS{ z0hy^}Q~q|0_)%x0VLUmhFj4ecIj~guYF2I7y}ZIFsJHgXE})JIU&V+LA9q9Fj%n0q zg(e#L^SR+OUk)-zbdSI@p1`PqQOAobV0hxgbMeZLvHVS;@57;>=}ryV%~LF=NAS0ftPJ0{ES)tdO4Xek!t1c9IJY8;$83l5 zW5kt*4)?tbV+cQJC4!@^tKrfV9;XV#_soy;6q0>*n(gE3SL^}+tPIFGdUo;977iVX1?Sa_t=?ix4=F~|#%EiTD8UZ$9*__ZZE3E<=Y78nK#3};eC1AwQ<3fppB;v;_(>Nb zC9zUPZ&Zaelh)QB<@$;?#3i{B-J*WuZK1(`(v1$xPq_s&C13U!L-!sdtBBm*-Hg#< zEj~PPsd|;jJg`J)h~t*^YSv2in}=R?aA!eQ`ZV6 zeP$WnfF~|9yR^dC0fXwSTJu^<%Bi2j8wnsvo0|zbDvHVrtn~bwTw*p*4=Pqj$OVNo zEp;OpUSam%_d>ICkmF5yzc2&Hr_MyLdDUCYp5v)A7nJB}V==3Z3{xDl?L09FkUKjI zY4ma9?$$u<(JO$7MM=A5-BgkvH>u}Kuc8vE{nBGX&U%f-L@TCkKfxdc=}}E~VE*2VF!aVM3mMWPP@MhZEUW5Pi%n>>f0-vksrO>^w#R ztySo0hi@ESllk$5p^!7c$~eV}we zD&f%rYwAsd@YR1HPB&Q^*RGSE*{GzY7EQAy}Lt5FD6+X3K6$; z6ka|U+o8uficxH~9b}0@A@rhsrQ>ZiCnomm2P#8YN7%E7<@8SoF*Z;io7mC<;123~ zBQ!y9p#s46y_9PN2gKPO+FIH-XjJdwg7BPyI!EEfzxJfL!D|EOl;ZQid~A{kbK}Yi zrKcK}K(MYBtOsK4ywBE z>5%%E;uj*$G_SiZk=@nGLhzizbD3IHgOHVNLi3#3?EfIf_CSl;Ot6L)?+xWR6)7*$ z=#OZX1E+|qO4`4e=(C@@!DAo$L^eE_$jkQPV;tRqeLNBEi8qiQVZQ8Ji%WR!rh~ID z3Z8|%omk2i&PmU6JQVAwvcqd@1`A|&4yX!ydSwg0!+ZDP6bO=qJ&7BAR}P#3A`Fyn zh!L0SbF2AjUS~Hx*hF>^oQ7%kuFqY}MloQE^DI10XFg`JHDiK42`1VjyvK~m^;4+~ zl`S&HxCzBz$MiaU8>qhd+g4+Od(Cmkr5Q0Rlqwl%$(bdi!H#7H_)nK z*4q>h<{ZYW#tRenj(BJb1{sV#*}{1nfo8)JxOW2kax}Gi(aj1JCV(q`Z6jd{)`+Gsy^u2dt0_S0&ov zk(A-dT8*l|Ic1;jx(CeYoZsRMSaHX^Xp@?H-8m2hZdf%#?GhvW6Nr~0!|J2lzy=z_gW6Bs9~qB;4Bhjdw~#Z8D>?2=Ke5Shp^ z7+Ge#7ann{I@?X1tJb>oS}%+44TD}r(Ab3UASx;w4PkMaI_EgMPzFe`xxq`k2Ug*H zY>a(Ksq?hR^#1Egv9C4DN6zjgUy0p3(Pni}+gAbefKawG@2M7^KO; zPXAe!c8a@;v%PbT6pTy))d)L#v%-C>S2R1*$rM2R@--#iU2#1O`|5OVS^WEJ$nuFc z`BFmuWBiFsdDoZ0w)4rIjT9b}D~Gy9e^DLHVVlvPvh-5+^6FRI2In>@G|VX#KU(6x zkbjj_Ad{;K`ibf}uXQl{ohA!$7hf?$0+_sq=p!iTiOi6X?iGzfgnFck#S0H^Qu8DH zIeQGyv&GDucj)SFR`K3{*d6;8YS=DcuCQBl#WU?Gxte0zG|wf2UWm?h>%3_H?QBw(Y%;NL zGRo%>z@&RMyyjI*nZnGg;`WUoe?t8bol$EEiGDnbS{UjsX7V+pG~3~db~riA^$vJ7 zDy5(r?p>_RU=4z%`V7gG#HLP5i?1D(RI{9J$bXt8CKD#fI(U%6G3SKuR+rILM_7zQ zZaG4gm-BVnK?6Bx&PjzNteWVZIU?4!H7!za=#+roSe!$qRbXx#KYW8)3{i1%13U{8 zoIe;&L>s#R>WY4K2x0?*(&vmNQ?E`Xh2TBNK{cdQsNJ7*hp$(BHHh=Vk6X;YH;hr9 zv77rbwHAT&dkgF>RF=>6l2poAN8yq%&*84`{#%Jh=+pil6db?x``Ea-z}4}l2ImIA z$~o36xmM3p9A}0!)w6B($wi{3*@;T!q4?qhgk0ro65T(%4gwHwMY!@3LH^>e8S6xisyH0T_4ORoL z11PxQ43l%7o(|MzFdgmG7h-}L^9DJd*#&7#gY!gqT!CPKegd-{HC{_W=KyEEc8HD) z2)2gAW+?iO7Bp#8pm+M7XSzrE0(HAsjaK+AD4d3SGiWc&^=8r(X3Nr1|HFtrRY2q>afMf3h(WO2T zrPuCRG=NP`#E<%ueZ2M_+Jhc=zqDV5ypS<}xfpw-*@j}_UZT!wftBb?v`Zvs>GR%T zVYC|&9yk~z5sHt;f77!x$fy|o$n>eZA-LqcT>Us}M$;_^vh}H!1=oXHM`b=>bycuG zo)9Ei@u?5e>Kx{PY;!wiY9s+Hw&C%uyvrKl#W#~;#$OG%xTO#md#EuJ5C zKUUv#D-D;IMtplrh%8-^F^F{2=Grc;6|MGtS(athtBh35I?BejDBv#PE)qJFc~j zrEupz)`8GJ0s6oS+xHp@1#V&5QA?JOO=YQS$|L?#l|1aJUX@dJW`~7A;h0sMp8rGLCw_DTmoZMBsQe(bwnj z&`~xrk(=9dck6xZeB0_@)D=g(1(ou7*PTt*oce@4(ik1QYk23aUDdoHIEC&+^{QU| zw4bOlX4iu|#nW4R(->?EtbeFIySRjJicDQdJrlu24g$8z0(Ve?y2RTBJ@u|(@Zl>Y9u39tHpdy6UvjiDa0!y9jOO*_K8a@+?;}^vZ4fBDm;-n(ujpv5D}gzZDhl zOaR8%%DLd9p=B&D_rN%gj%(0XrI1f1<4giR>#7~pZ~BXQB27OtzZa8icZ=H5=)igW zC@XAwZz;M;A}E=K{a~Qnl++vjmKQgUVxoNy{gJa-%^}EZQJ8yOG{rMWVqCSFGc)FS zcu>)!)`XjfI#&U2p`C@S=Azi`2eLzG(NAZl{fFz-^n+>OU!ggBo`Q@n;p8M8=ETUI zA!4?U{A>%;cn@?ptQIvp!u8D)=v#-1#YouBi%Z&7$E7pIDMR<^ljzL8yKql2yRH&0 zZBpC|ZIk&dss|2R&95HyFdJ6wKdNzT#ziNb*Ow#+CpHKtj;!+$fAa5*8CT00cNpDR zJ=hY_NNFa;W@>bzm|1RwnW};HQ}(<{jnlnwi>&o5Iokp|Lt$Y^AXEKuay`sD%e>Nc7{m7jazL2yG zA1P93!M1EiI1ImR&>bkxrsic~UVPQQcRvO?L~M;|4q;PKXUZG8@p^~U*(g;#n7K^{ z;RxmQsSjvgd63g5dUQ%K*g&GLTuY~7>8?Jq1#S7VxkZbY{?ud=dR4-^wnyp>=R)a^ zc^ASu8U}$kL4-L?ZB23z!Hh$HEU_yB@PJEEjTyKIwh7AtrmNhZqp^|SH=s)*X*s_NL$hX_iA^=&BPxsd~cm#9AijM zZ4+u9EM?$t`SI_wbfppG8#RUa6ELGwArF289Z!g~U^al3fUZ`TTs9Eruvr&?*PJ;d zubyRIrf!%n549Ru&b2NW#O;dBRdplgvSpbuO(2@6*afBKL8BLx9iRx#@*HO@(b^Au z#U z_36Ryp5qk>q(HpnBcH}n{H*Y6ZhYrmyIYEjWXxlNZ@TH~krH#h@0R7r z>ag~coFId8i@lA4r@p8^Wk&DF16%vJ)mN|xk3BGzd`ms4 zx1?&1ZN_`m-6V5g2OyF6ML2F3TZirvM)C%Ue{iX^bb#w_+l_zFydED~&vlQ`oy0vU z3cRA9zxjT=hrpFyd*E=Ld)5exY!d|>bD1zzo+lV~>2WN(S_ib#yRMmU z)lcRp=y?n}fle9T43SZh$J9~Vt zN1n&Bjmj#{*5j&@GaHmir9OE!9Exk9-R(T!mh~rR7c$hM-q)%a^Odg!#~#kF2f2g5 z9OJLSo=$x|r-uwCj}K&`A61e()jj%q8nM*`F&S@f!>;YdY;cbAsyA+7wG|T&*rQFR zV@>U`Y?4)lHE%q3r&8x_r(SZmSR1%1#&(6KCk*$}KNURTj8n#(esL;~7JxiSb_VKr zpP(4W30P$U*L!-S+{Q*{`%oN63|fDo1_8#9?>^&TnQiCoS~cvcy($4QApL&0y~;ZA z;20?7uJKX*)0EHizy^?1%RM7#)msB%@g+9kLv;ejj=hd6NP&82Q(Q z0%C6_E%>_Z#xnB(n>o&)wH{F#T~&LB>6ssq^BrG0g@G3tbUdeq&Grw`uHX*>Cp&nI+aj3yUs&{ap2DEYrg3cU+fF&zh`)G>gV<3h#hL7vFShEUjNG zc_tOC16gkFFvEZG7Dp6;-q?jBhg}XYS>J=ARSVS|+ zBZM+We5!^E&?v3g+Un;Xn66teAfF`1A@ZVvs8}Hw#XLoF?;p&xqnalZ_{-w-<{Eh9 zM24)*WrCOibSuLIVfIf%N5k$-8U(49-^)O&02*OlHr;(Mw$>vry|cYVdLr7Y8nJ!2 zh6Os68iW13Aezxlbue!v9*Gn1MxosZZ5TGII=LG}2|Dsk6; zaX_*uOE3T7(2j@()PTx}e2bt1aa7HDAC%rsPB|7|ICEIJlv^l^Ft70Q#BOwi)1K!g z$*z{%ERgO_gHsK4Vx|tR99=pAEDI=wGxe zVkzpK^MO0ezMpYcr#%?*teX~3u1|~GixlQ=JaZ3cJxsxB0^76Jp*Eu6`@pTW1Of-Q zgGG%J#9+q2wN{QkmOrT?y$elu+C&Tpy0CF zI1xFA+|`7=U4l2}iSlwA=RUACsRMP~&vmFRB_1_6lyjsuKkJ(2%RRF;d%JJXHeB?Y zSQ;qy404IQz9r}t;?uT@bB5gKeZd;D%w!v?DG#1~Kzop9xx;2CvZPV)dq-lN=Qa+j zK0i%q_if4F%|tG*u!d5%o4_M%xo;3(#BMX<@^#+U7DRpv1WIXiSN-dmhu;5rf2 zs&$Ft25)qc#>&P~D(B*IGfW@6!Sm^=3^n`$Wl-}-5eN_&_%fbRzE;i5MfD#3h}s9u zC}ilKy*@(@4a!ZEk>zszW1vrq!{{O-p{$zJ8b>%>mT*1TH@6egwL-wYPe~2r7myPm z#%V?wsSbr9Kt8?TDLhB#0m^Pv9|v#}^e-Srhb^aoi3IB^$vl<&Pv}6i z)z(!L{sNdD5O6`QaX#l{zFWkFp-NCA-)tEs1(bat=de8WB=*%T+-iNMTwvbF;b`pe zId#gOCHKJU8;mS;IwN!$Zfcwa3SHoI{d`&rnJ1SEvo zd`W%7g$DbSWsie*xu zgevm82n7uy=jW&$!Wikdne*aCZ_4QNX3o*2>hse@&;{$?Mo*bwF-KyMd|5L#z~IXr zEuu4v=<7GruR*9=Ryo^dqN}3|(-+hTr}NZCC9bfhlXi`r15ip`;S3wZB8cLwc0M9O03EPLq ziWKnR>jONkgd{*%hPHG4cz`?t3hFuVodC`RFNVE|-K2%J#+3nsKz91t`KxOsbfk92 z96+EiQ^qu{F>7>08jQrrT0%GbYdu?FnUro<+G^`B9eSpl&^&SCXtz2ykfQLK#or8soX zy*UUuJV92{o@Pb~IYWToALgA8ljeAst?@Pj_Z4>9AX$MRNFOxg0C$1x0V6KDSHjMO zz@nk!faZK6v7$t;{2CS_W4BTj(j10dyo6hMdz|Ot4&_r=um~D37C|85+K{d|6wOBJ z!~=sbxl6jm&u&u{8&R!EqI`Tx<@Cy-Mk=7XJD`lLkb`gvAh8j5va$L{Vy^Ci>N=@; zkrZ9}!>(QtI60oAexlsoTAkzvfIJC=E1fsCvZ^Tb4E59(Ke*ks3$)qKwU}4#*-SL_ zaCxJhH(53oa$wPVUc*-@wZ;0;xn>MpbLP8d#BsujnTvd%bhDgWiMGC%zQZYAH|=8n zo^cV&sZH$KE_%J1x!d$@h=KI`{z*XH$(H3Thj9B6`yEdC`kEh|)`Y#*giA$X$3pCZ zE+)EJA^!22P#e--s^^o61s|ml*HC*NP+ae^y<96y+E-m8PbnNxdCzf~X!$!fOg^uo ziKdm8uP+&7@%`;(7jC1e3kjZML8j9m@sb@nJ(Vms)ks-0e7FTzC;*;C+y_d@?+t?; zfbZaBOH?yFyoTf(-?j@D!45X&E6zEmtl$=f%A*iE{df&f+kx|X3harqmdaaU){W|qt9bT z3X?L26&%;yI?N1=uS*Hoe`?dEivkL%SF7~3f(OOtox6RMk@mSz+Kj$vj>lGS-NJ;G zZ5+OBlGR#cwR-FK96P&cFOjsAuDg?#`GVp+w4ZuUyJwjLV=7-*N|@UaZXeZxjo-UD z=f(<%jx6o0YnslqMLjB>qVVX^&8FH-w{=`8yI#O_YG1T5oskWJjq!yI;5XA-Ryqrg z!&=K``Qo!D`49U|tpmQBw=F@m*ZRV&)by;hnEM+LBN?8$tgaw2Io(hw_1|wyyy%sB zY0{1{Z7>ZnjWZ21P0kI(pI5OizjlpjkPUF>NDLu{LaG{tunS*Bcn)y7###^g<|Tl znIgXFOi+-#`JwPM5e=UJ;&rmHl9ODqj0 zTW+<`mq0bcme(!5G(_@M%=t1%lQd*~MUm*P4kT9FpK)M8T6hivEe2Jo2e?~hvY#+p?M$Z2}{oChIV<%sxKILhWz)f4j5Ncvl7WW5!)gQU6M-OiH=R41m z95t1)KW^gKUDVpTv2+5x78rja|!u_MtpKFYa7n~L7Nj9 zN4_7KU(P>h1(oxe6d)Wfy~7r8&hXt9JJCZAXOI?|(isZm=QNx94f*g9MBWJoGL=>G7TeDkJ7dGPT z*J&;WtLBZ~?JWPv?~^0P z4MaN(;Zs7q8@|)X5o+q=I)!LZG?}w+n0D>l=~VTK&qI{)+%i1aTtVdMG`n5wy6xw>%SZiW~E2P zQA7kwRGGdLjf;t#f5%(Ab)QxmjTNf>tmy_D zObZ1hTusfxsDCIc;Y375&N0KNVlBRdO#diQ_vt6W4c2U>gHlx_|Cj zSercOPrsBddATBIU}M7kQC3=5R{H%*6QIRQ0|jMSm6s=!og7S@jLezkzz#MB)-RXT z|6vm-fy*rEWMFM!By4MDZSszVS=q_NM(rIB8?%bLoyp6i&!cd#uyX=CFl+qF=>8>h z`z4wCzcRN!S~xi>m^g@lZS26dFLGi2Uy14eGbNq*-yDqopQKqi{_9xuJ9c(XPG)6i zL#Jm>Ued|`Vd}q9$(hwHjGfG%Gw1&`Jz*c>uA#C?(CUuFZ77NU3LcIa0ag=RSr}dH zgC;T_C7nX63V^9WiLUd(5l?gClcPu_gJ|0aWfiuzKe;T9A^|Lex(lV5wYGRX?Cm%4 zj$0{7yT2doTUxe2+uA;7j7L|t5)#`_V*PNUvA(>d_sly^`lEXz70TO8x2bxQ+$;c? zIEPQk&+mm6)3&BtWsoFI4J|DVEy?2W`m6F9wrY%T1t+91i=9gHfdXFhZ?|&uX?`8ij*JQ;<`z_8A?NwN6(ffTN5Y?4 zUQ2!Z^Dp`Rfh&0+tN-06##c4S7G~MZJFQ}J$wX9s=vhXhXOfIgUtr|9HWv&3+$C`} z+T^{(B8xPzI{$Z{IX;L|4- z;6615FDY?K(_c}3H2lRYpp^^VmcYfVtJ@lO!wy0ubNQkrz=RBs%xtL`rV_wr8q1D@ z!8SPYcNh`QI;!78Qz^V}qEqFg#_1QW#Y{u^)-IhQ`wB#;zAn8YJ+m$A4}L!VD*F|i z?>$O%a*M_%zhk#@T0Uw|$-ZLwR;lN5+A3z{xYf1&x89g~YqM;x#qA*oP2EmP-4GS} zwK<{7twdoVA$PdO*~ylq_Ujtkc`oz4EXDaZuEoom_CJWcX0-n_BialYcDwz<8B z!&u6+b9K|vsN+1Qw{Kd}mbrdSh2)BPhJ;>qNo;J*(fsuQxw(UQUSRqN_D+pl+mPr{P)U6NcFX6}>K$)<6Wm;1dGLBS7KK0YY#3uph%_Bd zJ=6_e2d1_!1ra)tOz@$I9PP=Rb>2X^>-(?)%#UN^>R(k<)%O{sCoI0f@(B8;bd>Br zxnlY@3~1Let}lMyxu2K9)k~LeIiu(rE}eC=WPW3RZIOi~pvkv_Yxu?gD-0?MjV*rq zWz?_?iCa9qv|z!FPou79Q)Zyx=AFnL*Yzu3Nma33uWFyVl*PX#L|n>cDM$2DJQmCn zu;oV~EeD1ODcq9Ir5`@{Id+&N7ZO#~RfRnL+P@I5_;ngt=U(p>f_copbbR6c5!&|; zPU~=EoLeD+%JTNC)g@~%)M(HQUjVI`I>oUm-bXmC@d~_(c-05&)FFQ6Pqie!C)7sQ zFsW_XsNXNeu9cYn_A7^bBuF?;*!2FZ6M|KQty`!(U~u4y8--O5(Pc@{(3awD0XHf` zyTvKw_yE(`th!B8Hxtpb3ZzdOZ=pIR54j@4INf?38*U$ z41Rlj=*PjkGIZRzlmitz?Do^Xz{*Q6V|a}b$i`m=d-+)*u~LXG`ahay$DG17i%G3d zl(X+Qk$T=y+QVJe!z}oP22(Y^Z@nuHD2n=d$clw;5^`1JAgp+oWQ^{N&=EzD5q!sC z5DE1`m%R@)CpZx0JBRlD066iE^Fgqd?;Lu`Otl26b+ur&E;Xsu0A52MO}B6f*)ApE z?FpVq%GTsN&Uk#G_IOkqtO9nl1G=2=^F?Q^DbcnmoRA6h38}zZxiJ3*;URP4vix@`NgQHwB|s)Ud?nAjI7dHdLIg z7~#-p?0#PnKQ~W7rCT7oMMH~LMHERfLciKDNA9_9GC;V~bS5nsT#;yvT8xgcxg3-BR6X6UiDB=%^Qd*8no zG_K{aZB@^)g!=2p$E$v}Nzw;J&P{z6*_*^*5v^7W8NiY5SwCT0q&S6-e+|taQU7j` zJdw^RV*~Swwj?s$VqVHD|IY2wY85*?x;q?(8IjfTRiN=ZqtP!%&iEhY^^*moM(w74 zX>(T=o``edr2HoSwAEijBxaO6w#EO|DVuLI;Ur#h>zAf&jx$Lwx@S`ipiPHPQx4a4oCBJUw z&qr3Q+OqS={hGH~6U*^!1Y1s6K*eg0d8W!yd!w|#A%N4Udd5IgAYUN3c2^-m%<2r4L z&X%BtCk#J4z2opKAEZ(Y4SJ$cbaCrlX#a5~>UDK+x7%jKoRF=5$gI_CRW+Z8yG->! zIxMrk;C_o5g;0#KW3eF(tYRXLqUJYfOGP3rAiAGRWSHI;adRkQi^()IIbSLHD<$Se z65`%g`)a%XT|D_>oFeePl_#;lcs5N(6x8{rsW!tg4ZqQoICNw$jxle;{d*%1D7bT5 z*z{@HFt;U&tJjmfIaZPkP2^Tq*X0#SjxKmX#lToE?Sgi-Sgdx`G3__+FD2@XWl@Kq zS!Geh8}86!tyW$(Xv-TUvq1F5_0S+9i^l55w#$_M>boDYsE8V}r#F@1KC}b@EqI%1 zU%F$x^jfffFT71Go@kAY2Gj9zkRgAkgzGXd?7)MG4b<#`3 zSqE<@G?%U>EqTUpYOQe@utP-P&Pf-~Cm;&h*1CTl|F*?7aT88Il1YxgwN6d&IF#q? zGfVMuEFT`h^E@;?EZJ-D8T74B-E`qqj}i7Lu$gj#|1B4ibuLv9&yX^D=d~*ypc&~V zu=ZA3au4Yiy?$QSSr7$*Gjo&dX$vRlhStXMjub{SJMrGF{bSgMPD7S%hOjRAeN4X!qrh5K+ZbaH*ZDX+ zCBz}fI4N>*EB=UT|Lk&#j>vpThm-9mXpEU`NQjMT=$^QwGb^cBtDz%{&xESsF}ZS2 ze08&rl>DP}AZ1)deQ)KBZrRGzSvI!|k(YzhG!sPB2AX^-*mXh>Ofwn9jMEehW^h0c zf7)K|%-6dqgMxtyP+CX$w{Gmepxb@a21?;QyR`t4oe1Ef0=}Cg;Aj4W0``BWh$T>f z;2B@+e_O=z<(dETCI8>Tmi>FAG64Tf!2xWfY~rNNtRO1RtYYHkr2DVl>%U;J{u{sa zpB!DF0t(lE%h2u6oR63n$MjAwGlxYSY2w=`hYV_$Yjh0pMBv$3yLHV%oe0`dMs!q* z(qnG+Zj4{3DM6SJZj9zj-m+dEs1IT;DA4bB$gd z>G9-iSxDU<-=dySo{PU8-njXaxoZ<~r)CX2p)r(n6Bqjoiqo!UExSKu*{#5`v7Ntd z%`QeRsZZ_m8d7hjFNB83)4MH_Oz7!#_WSw@_oT;GKZ%LrecidaFc}v;5^7XdjV|bS z8Ev+4k-k`!xTr}#QV+kav#R-f(VWUn?VzeQGxIm3){jqap~6BZZa-2d_cy&YCf+{M z{t$ITz^oyQOw;34w#Le2qXXIN?}jZU`B(N)YKCXkbbWOr)spKf%dMYctnP>(OfIm4 zKQ0sCse3F)lJQ&MG#qQ7^oxJrL(CMclXoqt7?HOBEJTH;>92#mWY08K)T3&=&QIr! zXdO*L^X=5|qU&?`^dLjdZcT2e(l9b+r%O@+y$zg|FDJ%;$Lx=TIOr|2-#2O zm27lf3?30Z;9GAaw(F{b5cE+adF#xM=;>urcjEg7HPK%WBe^*YWx?gcoNUyqZ zsC+b@Dc);2er!%brweMNfa&@61?3f{x{ZYWC`N-g&oH{GlyPP@@iuas9;&=`hjxt} zl6JS=J2DU`U>orpiHu4sl0Upp4=;Zey3(VOht`e~|66@cNI}O|$%X~anAp_859wkw zEkO%R%~W`s)e|$Vw@!gPGsxw?VpseF?A>XdU&}Ko&VsT3gfMKsBCFS_{V5*eBXJ@- zVb-CxsLMb%Py!8wD_vbMAAvi)h>q*3%ZSZ-==A|UmyEG1Fvo>~JDrW3;cFcFm$jgF ztJnHc6`u@7-;uyeaPQaV&zK_NE|T$L=VKDo7_oRtNh9%n+okH;A63>jv?_bD>~+e2 z!|D4ws4QuL+VWu-CYd_#`>R&CDUr&i5;GJdupSzxg5eu$H5eg1WrbGN^OfvOAl+m5 z{__fjaC?QkajFQma?B2F%jw1$3UhO7xX9xhsg`^69H`NZ%~E)__e^+gubLR%Z1%pE zZ^a7w18V1N1tSVnTeE~j_K61*;bpkFU^}ywWkP)~h+922RF)8>kT1l?)TV|#30u=O zPb4lyBufV~xpV`kC&z;rnQ})g`&^~wk)Sr@65Tl{=2Iu0lmOQWQ4j-vnv$ zdeW|9>h(N#km74NJXUIOuoB|e24_Cl$3)2>KMMZkAZJ+#x1t$wvmPGEaimrY%gq-P z;pUt}&%&D6gpMFfe$^H`F@b&Iq;&Lc7@L78!&f6kNW9E}+)AYyPuL-rHOmq2dELKi z47zvA!q!s2PBX_kA^ftlQJY}IS79z`KGHhBKq6P2XIrvk!cS9 zWdFOJ2A`GyAOmLs`r`zoutbx*hNWkgrH4#h^W!@HNVE*h;POahNQ;pgUznHu;fI>u z;37Idrt>g7rGqO%s}suq*)!7dllPD1IF&cstE#zXiq7^<;QfRi&!Jn zQ9cEfiQ6?dOmA6XG6CYzaFU}BDMOARiMMU;&dDs|*Cy@-;jR$scW)>dQ2ZBIz!Lau zCJ(kb9*%Nvw%qsA&o-oGkCu+DGi+tLbcYlok6?#X+}!mH4<;2{9i8N)!;Od5Xme03i4EmKM5pv8TJr_;zQ?x+r#TG?XW2yMRTC=b|%UgM9 zDI=w6nnE*%P*E@Q--thud8>UHMl@GFL9q;AHcF2_|7p5sp-Q0U&WS}j#iI@@B}Jlc zDd;~NPr>WP%U~Y=zSHiIP{(}%L^c>qK-XC^uuhB;jjQ{$F?+V=UB_p`%v){t1w@q# zzpVfld|RacDGVd=iOBciFybTgXIvvHeLT^Kw?czp; zRzZ$jVKAGr+@sc3&woq3GRfXkOlpo~jls^D&CGj6U*+a^BV__{r?G^zi}Z6Z~HNDf|)`YrdG)aY);8_U0r z7po6(euS!lpAfQl7`Wa*Ty@=?xz6VuFQRz$q5Doba_;Naa$k|Y&6L7nf7|UXuy8>gBZ=-S1Y~$bXaz*mnbQ<{5`8kCi@OAdA6fXb0?TJEW8435W z`hg*+z@%liD)pU-L2wfH#RpwyyrSPnUBk?BgOmi)YlXaxqG^3K9Ou}V!A1G&S#QjI zlJ7|dP>n(#jfW;}T9%78Kgkx797yddU`0~cbJ${~o-?NyQww##c!y#^J5Z>RYReB& zFO02{Y+#wb9`K6s&KDfu7vdgDLfoPtb~~)4a((6BR=SDynwT^Q*Xt1pq0y)P2O5!*f!F_JG>PRVt!`l#Pv|Fi0yULRn&aEb1R=z0>aAXHCy@c}bmalXzYSY^61VEQ z=4cLqEz8Iy18M@kdh|rei7_zBg|-_S1^SKkhPh>>>8tYEAR>MXC()$NAtUCm=jy-b zxXfyW_oWA*V>l#W?7P=E-II*{vOtZ|l1dy{>hVry_X#WPPqBZN@-K1_qll?|AB%QsELCU4z_@yWB6XDa zqdd;C)+~rhTH05ui%yX2On($HhnVcDEGOm+v~l zT(oFEd+7z+-@pHJ|K8FjIi&_SUugcb)&3GO%^;aj^1>pzHk55@7%|cn_Jsu4BL54-e^YiDm3j}`+_jJ3UPATJN~F&<6($aXscz3*KMsXUNw3MW4xHyw;)E6P@!x0+D40SKC?@|emQtm+mPNF zG#NqmuA5tSXC@^Jt%e&)>+8I_{b^+n>VntC$EJd=OmeMyrytyF8w?W4GBVs_)4^(J zwYoRkYtvaub*8CCs@ayCFh5fMJWci*tCx@a{AwFhy)>A%nce&5GZ`26`ePxlT@t!z zWrhe9Z%%1Iq*qRi%K(9HJ4F;(;0QJ!>goK5`aEVl4rzeIhs>J$dQlAq`;lChoDye5 zOg*Ud;<>0%XL8#HFKj#$&hkCTe0QpzRM<(}8xEFU8RIV%*-B+%+S*ap`%cZ^R{^giWy0iLk|}(Lj6Lp>b9Fo1KYtIm?Q%jd`@!Lb#mPy!`<5D*ukuo!X;M{hV!#=NJ2RJ(@$c>Nsp(vK}2r#G&SO zac310GEJYiSw_7xr$&)`&%#5PZEmObt1!2{M|2e~A7+-OQrrw-XgkTF@i1r;Z)$0| zTLGDL_F9Mjl}AIraq)Nb6&#-p5mW8t&oL!vbs-QDN%uL|0yIm>AFl+r?p&4+6tK%o zbF&Q7<8Y9ecOrzREaYsjWV8yj^%5o&>Cnb17swmNY*UDr~?J<0E zL)neh4(>LEEZ!J;axmG_&dZ>fbg3cso@QBlr8FD=WwsVppw}OJy78{v?*#`)N`b^B z_U{H+4jJNn)8f^{aN5w`e_y(dj{exN%Xg9XA!~0jlYjhnAal5og;EwPd2=yZuY#}C zlh>^n4ISS;PWAYcSv%__^j=QC4T1)0%=~9dtiVb!vVbCDN5KqyjS^%|SYAYFhk2Z7 zP3zR$Nx=}fqG`(Cc@1fSxDX;n%3c2N1RDmJlds?N69t-&A_Qota4uJge)i?J( zgE4r$L0Fvry4OQ(g}$o<4l8d|^b=J{nX1a|0~}$<^(y*KvOP(F=x6piNqP;K`X8(` zIL)=kC1RL}#~7NhvNhGhU+EU&jrFv|G$;bED1vj$;rc#L{6q~I9UcC2Q`m#LzO8e5 zgM4*b%H!dfKf4R>M$Pkx!o7Wz#aMI~fzr!GX?VBGM zxsyQ(Ybx#!ZM6PL{5i+Lv?3a5OCGMg!aYYuddPlsV!vMcEBTJ3sJiF%uDrPR?BA|; z{}J9I=YJ10LD9aNegME0YisM@zNHKci%L#T_x280TiXE6<@Cg6`3Qh50$6(h2p|CV2LKVu$*I%Pu^Ss(ad8RJ z(J=tfk;urHsHo`h@JRIZ9PI1@0Jb9;88rq5wxOXBKff3{IxZsO8%arN0DBP+j~u}1 z37vdGiL{*49o>&(z-D1r-&W zherSd<84Mp7C*lb0Ra(!zDPnshJ=JdKtKow2M-PXijtD*^JimrcAk=wipa<~K0dLK zkVpW=4*<0^GXn!i(bCe&Q&ZFH>l;Z)X`Y_`)YLTW>>xcoqwn8CtE#F2{{;6mcy;8|E$k&*&T<|r#`2nq@#BctNu69Y(& z1O%iE3|!jUx`c#80CXTJ={qtqhKh=+uU|uZd;1+6+(kuY6%{oBTtXqa=Hq`i`Cg2O z|KyMkaBRuN!pKBP;^Y73m<~`p>3<&6;p7IeB>#hRIv}?Heo$wwt%yQBndaCFuE}3d z7~%otzWllBDi5~l7~eEIO=rNc@690of@~xTu1Qeau2^{aywm7+3xA!BKcQSwdE7CY z96cKx)N}(G2EQa7+_zU++qMzu)v5 zKI5>TsVr9e>6CHv`-)h|Lv!hxVE?#Ko603yx$hYL5NB%}Nwj2c2IU^Dz zQa(Su2;2w4$CRzC2pJjDl*x?et1*tP#!4BISK76SoYfW zCtz2DX?gYY^R(E#q#**&ZS5E>p|>*ACTCW7Nh0~~a)Gwhoq&uRT!>)EcOd$%m82nu z--x9=NY{$b35WBEt|>C)BMw+a&6F9gI44{K{LoNDKD_dp$bA z52>RMDgH?L`p!bXu>CcWh1;krQE}U;mIO<0L9L(lSdw6eWk;}#Mm_jH`&rjVvyx?*DDUdY-*x2 zwDuny2t>$FWj&PRT|eY_*A;g#){}C7PsDkq`x$m|7EYJ1dLSW3jPXh60QF_+fIDq# z2_w5z4{Nnb#yU40G3>8n2c_6~K16xuY=lKJ!ytdq3r@7jmrcBdHO*viyqv1)*Nvr$J(mBToqVgwTZfRwo zW@glZVVh>H4IdZSHi?M)S%K0lw=b_Zp%@n^;c!BXE-arvzUh$Uo;_%)EK3yG?M-S4 zPCo`&qKk6gIUqKfs);z1H}Y)&FpkahZH_*OTa(msZsRlQ_mgQ`4_9 zyW;(uzi2~-ZdqLits4%IKMyOOT@NnvQQIia70l42U}2MvCpYVrX-^SJgk-#k#AST9 zD*nTeX{8=cgd|^o#Ll4UxRNhhl5t+PqGz5*L^2FfrSrkbQF-4k18=r72FG)kKj_4L z1I{M(4%$rQ!7_f*j0Yot79*G8DzUM;3o~rsRaDco^Qk^yGc^LeeXu9|g2T97P{D+d*u6N^w`j4iD_+ztZEnRyH zQzGat<Xsde8Y{)X(oE5s|kfrwPNgayEtk`D=V1 zo-uxb|CBd=RGczIt0qU|c0Z5*rmGg?g=cZ#+?Lcm!1z6oz;R(CDM0NnXNaGM>oT{t zt#Pc^kDU4*w2HAUWW=b%6q42Cz}Q;m9Dp`oKW;kr+`d&Co1$aXd;*!qh_cT0!yppH zPLpn3g`3vBB-bhtCqi8yV*M0m`uHtLOHQI(z62Ae>dw5|%krU9+-p2GyFt`FF_!}w zA{O3exF&)e!|Qy6O$GEAPo1NPA)dF~x>G1e?KH5>1AHdZxO^$vymD4;D;`a@h3+!2 zP4fr5SUvb|E?cWfLyC@mZ@y=MeHKIb3Bt#IZ{P{#IfH!gM%?wE8C{76RQ0I23Y8CJ zFwf-JOR!8lqI*5w`WO(G_}aH$hgu{{wf!Dtz$fBDj)y6npFkF|JRjk+bJ6p*MZE-~ z_2y-U=~T~Jt95zb=X7D(7kQ znJr0XtYVAEo8T=?-dzpN(sS!ps`&$#ie1-gEfcvgMT1-KqeMN6ZQ$iGB~-(*(cnZf zE`W3wHkI=|tBoPs1+)EPVk43sRXjh>1Pa5;Zj;6@E2cw|^c_qx50@`;z=k#-CFDxl3}@bHDpruUjtS1q_NFS%Tk zu8>8vKcsVX;=i-U-|*l$~iwH@*U{CT^zT(C=l5;pn>aJ5pVNG-==|p zF?Vv8uzTs1O+SKP0qt9>wV4tsmfbX>CM|K!+O^zfxc$>)s4Y|rw^)aPx1UHO%J0}HtpGM%>_wRsqII? z91oB0Hwh!{7o2gbP)7x&%3TF*iz((Pos9Oe?ygB{+0evDs&Y;4b8?55ZRHWq-0?J> z&ZyW`XiUhFrK;ck8N=vEJ-VCNy=n%ldxR##to4nr-#sBd_g5>)_-%o37+1``Eb?-n z!&^%_=&EnP`R725lqfeuRz~WIx7oLWO8gKT$gVKD1oUcR8(-28FX}u5O~T?si9;FP zH>E?Z*%&Y3XL3+F!7~9`R+ObF^!`f+F06(J97!^~Fug^elkB#bIdPV4YXh!I;+OO8 zOy!EHN~<|HBu1LJ*uxhZVwyaD8~sfKQEea8-#F(xm65nT(_8s-@tO=!a4z#d6WnU& zCzE5$Dm59wfP4x~iP%XZ=aqNx+q>>TlaiBbJ?Bo<12vUy4ONfO+8D~SRcZ0v7HCFR zkfgq@w2dm9>eS-;4m8F*D)J@IZV^s|MqPUvzJzBr3#AjP^&ULHg7y}$eiH2g!@3G3 z-z2PieITWB7Aa+`hW}GZ+*M+$W0PJtO<&67(h20PaJSp(CpX;?a&P66OP&@ zH^#5FNbP)`ezj9hi@#SbY}w-mzh@X#x^ACMMbrVsQ9qhGk;+$Yny;12w@3s_x_N5+ zV@yXSzOVTf7-xXtWSU0goL8L-Xe>>BfqhAWOuSIBGTsUtucO0F(UGLoG0$#p!p!w( zhpfjc=ZdD^n}zFJ97lwcx4DrwO3zF})e!+6062~RoqwtG!4@+!d?(1=+6Ts_gxk$- z-lptw@!Y~1v_x3t($#+w@$5xKab5}epxD#OM_|~$rS8rKoln@yn1x>ZG1EQM^Lv8_ zGd!>W9F|O7M$wLmiRhB(vEE?nzSZkIDAzaYH)_9bGtZbcV}hCfeVsKc@_q8*OKY) zNoj3i_a~`IVnwkX3bF8-JG*S6Z{Kj^@YD~OG4t8k3o!p6BKSgP)$p>8``DTQUAX(+ z5&Xw}U;#ROA$O)55)(zDWOY??flo@{Qt-Zx-TyEw6oJTTA!LgrFIR2cDBa!J{-_q_ zfOEdPmgeS}R%>-|rnw?ENck4n8a?2m@erWAv^df=Ff;Z1Ml4#9#fbG(DJ#v+`7GC z#`B~!siPpkEt<;P{5xvdfbF<7Cvjji>G}P|`dhig5KgCmwrRg<`Gb8@%eaIFeN*sF z&}Ie(F7hYUrnR+F!KmDyx-FBwk^8^6F!MB9NqZN(W_?i@=eD(b)qn7Xk5GCMBu4TF z`RDIa)|ELtbIzWJxjU@fgv4qY(SXsuvDLRu(zU{SsbZE^he+_us%`oZ$$DNhh7%h> zI2+7NUSi#0Dk1xPqQ6VX>R)RvJ|A|YLxQvWEZU+y3mMO-A<-sB5%|zurxt(rred7?QS`^Ulug-@Ts@88auTK)i8w!Ybs-4#{y(IM+0QnhG0seqed#Ol`T>fX|+u zr2Sxk&YRn;LSx|^j0Aj5R-r;R6i$=ny0&gxxT<@FgMIqi0~Kd263=`=F)jG*lyOm2 z4pvV!%)4g;D`IEnL7_9F{}3IC(JE!hL7+B)^1@bnsss5BzSFkEEyxhh_5O8+0Dt6N z5-$5^1ADbC@fVe;PR70~z(LhA&Iun^_)+?}0dTCc!JcK#?EbdQB;!NlH6OT1+4Jg5 zl%4WZ5O24pHSJALfWS*ylR$b|b)9QXM#9?Fo5^Cm!GRNdx%ufAjn=3OGuEON0x|6@ zXMOM~u&BYs%l}?I!Y2zj9rgom{7bgAjG^B-*Z(AUj;FJ}V>}xhU^?`wkmiTqO>(z3 zgN9Rge4owOUM={O6TiL;r#58R-wsnPR5eX z3duU6MI&shxCRrWqgGvJVzUlCL;5%t()+Y+U zzD(f*?EB7?ooY<>dAH?XKJ*$^gM;z`2tRXgljv;E>`$*Ut)C*c@kJIlhfjx{KCnA_ zw9ct*3pscpEVb@F6Ndt8C}Ow&X_sbUsO)Tbv6UKGr{}-Z`!`#jTyLHIMtK>HHV~Ci zm0U6BsLwK0!8pH|v#qUw<9)D@ei3bqw|k@uz&#>+#(>%6dO@5 zq78X()A&L=NRt6ql|Ip@C4@6HqfBMLUcYRb3-+1Fp+7#dEf=I;zZ~(FfH9%}?}TY( z(m$Q^88$3Nh-b4A0-krn;^7}W2LEPWz<2TJrjGgk@(2`D{6AX6j~zq!#Tv7tCO3a3 z3pFGP`!a=I{`vpIpY3Dwv-5|@mis}lull3c?M3$eZ;N9-QZE%b88M~8twgh7eFjqg z;=lPPgW8Q=7xe@Rcaq~j4K|ya-R~(M9+$qQ=P$QhU-HqsXc4<4;BrpVZS&RYHpsCb zz3x(Zt3B>6-MgAwL(WmZ*+Un_^YUKI4EAANzTs5rc5^F%=k_jNh)48Um@6*V`cHSm zO{MyE31xZ-!iNvT&Gcpbo{w3`@qC_{<9;0bi+AZNsl%IbD&>9gzV{Xhk1}vZWvASc z={cI!+FnoR-<(WtRt)-y$HV*d_8|IeJ1X6LFV4sUf$y1Xq^E9+oxazd?m)V@(BQQdf{%YvlUl+WWS_vl(o`<@nH8Pd`uTw#wXUK$ag% zEsaVSp7wt_JwUqUQDqq*@kT*99>B2V9331z-qLlO?l%1_@jqePTY`XJ=8sOHHm-0& z>cF7w_OE5Po0Zkf@0)&2vOOk)q`q_23*55BvdnL40+)Ilu7nB+YL@Sg&rG3SVi0zd zw#qNUTE4$@J@PtMJj<4VfC8S&V@Y8JhKet z+HDh(kuKn?DBd<0+3b7Uo*5}+64uDg>hrYDY(?7Sb-}A!=%X}idglb#ndz>A*R;CU zF6J)`FQ~av`rF}den&O=U zuYg0y(nWasc@8;^bC?3Jp-~TV+F84t3rD0y_RLZ1fg^-`=NITE6;066=iK~^!`tbp zvJ7?b;e7Ae&X4)6vek7^(!V>k+iWotDRkfvObA5Kh7^dJw`^R z-|yapKArhS(mCfL-Y)Ak$ywcroXGn=eDl5kcJz1?ejxMqxEYwRE)SvL7AqGzZiHvf zL^$UwHz8rByGqgxoG(04xt->3x7-{Ytqtq@oOhNh+)`pVA*YN>1HJxA1>jHP>X|f@+}cx<#{;+T)itHi)9P6ZDLUM=&*NIz zmF*M0hQSM9k zEVoepLO%i;-?ta5Kqq+!@m67FVdAYYsn&<0l)u}7V_?A-0}|?UIpCg<@^GVsW?V7t zD$p`MU%pHpG`;d+C5gO~TRw2HP*XJk+*WwN9P*qUGmIB?>@YxhM1NYXX}yyd(DucM+rlP$>&H z&&!IR+|NmRc)uIgb<@i4SXVBqK&0{~$LUZ_CrQjwt*a=hBdvG)Y8LHj`}W)@np`8a zAHj1}_Si)>e;oh8WGG~G&9GvIZ>tB8iQ|Q?-N011cy>JYZI4JVI8L4-^0%T#NEYq= z6|CR-vsvy}`!im$RPE;w9jh*|1SZ94-)gxw=obCfV2J4D2cKkC5s3m;vn3=RbyESx zeJe9(ukh4M5S;eOGr{=`<@-;mX-LTg5EyvxlUfwJR&;by9{)sBOJSc+NtIpUkf zNM_&zOFU>=sl~ld%pWy?SpQ3_gf087`CBx6hu{q*vBF*Kg~#H)=`d2vc%mtKY7DRw z#rW)Jv{D6+E(86&eM_;{X*kN}paJVW{wee5GvX|_zuXwprs!2WYHmDot(T8dM!+H;vHcv`c&Ow&m(*&8&pUXqTGmd;O zC&4~<4S%=C%Scs8AFju30cCojNRU)&953tq{PAmCZvLDeGP&zDryGB%LkqC6!^8v_d41Mg{S2Hu z2Vtykw@r>-G7>;+uVU7^NIo-@ra#)dlc?FU8k}RFYUk)s0)<~ou9Yfg#;)a9b z)m4Xmco-)g>wF$0q0ZLWU}HUqS~VCCurk!SJ|_7754OGnD(WrjchnIP6h#^dX=x>; zrIl`^k?sy@0Tn??QfdGxX#|E270Dq6kQh>=hE_UlFG zi_*lHt5K2263(MMk_8Q`k^zTOddp|4666n6q}`^fHLq^}nT#cJ;)YDIj*&|o$KzIzho z(SyDS-+uL~axkwO!NWZ<5(#z+ks-JC@<4{_Qt9^5)?A_8S(A*WKZtLmt8#1`9K4fc0ddj{3Z82VdpKsOf?PA;I`Lh}}!okJQwr z1Vd&V1Re%CrMN{$FOnA>1e`%$4tWAdQtMJhdkBt!<&#N`2T`o<)0M+@tHvs1#Sbl^ z&9!L_y%EJ$OThaU=)Q~Wc3(H(S{_Z(ecd~&CNfv*Q6x)r;0#pdq>`+q%g=E3n%DvRS-<&D_k$@;d z)IRY%rnv@D!)_DGZOQ@1>HJfiIOoZyTb|580FpL?ifS`XXc;|PpT>C9*^482So3UE zAw{5|(}63izJlkjYP&r?5%v_l8>#F`(&DX>%J;|txm03V>$4AyRyEUJI2FsEd`_3P zsN-wyJ8G>H^Q1x8ewo(j5SKv!~a#HJB?@Ro4# z&RNlV?zr~c&HDu>NfIn7T}ADX!QX%f_^{Tl7RaHLDYgn#qWju>sK1iIw+dDL1Ei-@ zR&0L23Sl`*kWL39zf+MCH{o~vHbx)aO?FIOAN0DI-&x1;EG(tnK> zPRt>aVt*C8+H`V;S*_M4zave#QA=a&VeWZ|)wV}iZQ~tjHzPFv0;mBK7KxBDVp+nr zUTO8;?>R^P=6`|Qls`0}ZMpYHt@GmPPeGWzueHiHTmSOTc=*OSGvtN~kZj78F|L`@ zIAjYzebOTUPfJtA<_k*bi@zWTG_}uiXpGr+tTMga0SR!p*XZ+=Ulq6w>Ev5=f__a& zxPa37Szv(SXf+VoQH%KaX_~3PO*nsCBp^=r4;BBVpJnxBxW~YxPNvl*jV0frp(*mR zF*}h@tke@`9=}*dJl0>nEVYbFNm&L~Os`aD!@GoYh0*nokR6OMM11bZiblaff+k8% z$eOG`i8(&LM8Ip_nt2ZL`y5q!J}%HNGB7XoF86v|2;F4|eB!H(GI7jbF7Je4KE0cw z3(|55G~D`OpX3Q{ws9sJ_G~1$)%bYDeJhrEf0|9*^inf9nXHtRuGgGah2nVWz!M67 zHAqfW%*4uEO^y1?j{^MQDa1#2ue~{62vEIsIu)NX=W=NNiDLEaGM!qRH7sR$j+bGj zt^DWvGF*LK5x+b7B+GBKc#6M|)6T74dA;tpsIM4}7NWo|6>^WDR0qK!0Um!H<=!KF zKyXJAk@AY{7pQ>A4y$(EO&P+~uSxq;-gIK*mvqpzt~c}bt8NY|yPonAY7 zp;KFOJJJ4pYb<*N|yOrwT zZ=r~O`W1aWNo$zHW^Nr+3jq}|TUTfoCl-TGHr6L#mqS5VjC}O_IgRY=W>_bfnOK43 z1&eSagMtp^7=s?!%7p~q6n#T3c}-_7H3QLo%ks`Ibk(h=Z?nXh{-`U=_T6FyZ{OmG zYOiFEee(mcMsfpgLvzY-Kb1)F&U4$9>u!^h+Q^N*O6x?_YS`{PN_XM~B@}jrkncf9 z;K2Yb=6DDv=9TEPSV%>wl8TBKr<=g!i=N!GU(s1P=`K|94=#hD+D}iLP<3msK4|Z% z;}uAEwTMvzD%B&d1D6uu&D+;BW(P$Bcb9B|fL?Z&xDXUR+JlCIw~pxofOtUhN7?mU ziWgpeZ441P1LBMzdJL*07E0^uIl0rkBdL(wH*mRuh71CEbuUDPpWbG7qxoP4VZlQ* z?lI|DOD*K~O8cSNK+_>kJOqNIjFJ;b8);ZLI}!O^#Bv%Y z+BC+t_Skh7H7gPqi>pr>iW0A&Y98KxJ0u=kkeYf2s1VNk-?;iMG-7c2Ta`A$L-jj$ z`uns(D$pp5=-KWt<3PUOR&z2K((UB*Z-5zB zJ9XbDHQ2S971oWCu{H3PHVn$6z~+?XB47ARCnw4LwM81(*?1XQq|_U$%@NOx7ZYo~ zR;ZSyrgdAx;*rafzyryKN1Dya~aj9M>@%gL5dJX-vb>-X}81J}ch% z?k9>zsjGkTyIN3r)P4lry7`wOHJ~tU)P%C|!yiw9w7o5HQ)tG(at;|uvO=Em$yTZh z*k_sRky+qnXTQ=L$tc_s$4&5-chT4gE(9V>7lP9PTWh#RKovXN?0HD_&}Lek(BmY2 zuBmsR?Uux8l(T>6NA#ip&X*YPbs@gJQ+B1R5C?ZFBYRT{_d1>8#6By}Td$?Q4x7f} zHpJ|#u>MX+QkUv~bR0<^Oz1JGOF`p0dvxUEp67Wp6U?Aq;1YzKp5Df^slM!lEa(r} z68A`wrL2-ptv0kY0b%K0w%N3!qJjRfKJNZROuWT49tC;nXm4fJQ6jim9uK~>15!nz z>--_G^z?+PIPq%~y3NMPDtND@3NRjnJYsPnd9`t?<)rI9L-U*N$p;~$JNrAC=ckG$$8pE;-)kI4hg?dHW{`x{ zqSjJaN&!M{E`$71=X)^i&70Eu{ksfT@>+R<_oN&$Vy&UwOg#^Iw)av6tA@fMfj|q1 zE{O3jYKgE~gDZJN3DioCj#O}@>x~fZP8m4!UXVtRNZ`dy zPj9gEGll59iCb=~cJ_KIkK9hbe!&HpMgop@{=4V&%8G4bGQo$&n((ZfJl9i{dADRq-m0-w~3#B1P+leFi5$`D?>+BzW)C6 z%`%vaVlXSn1?{-BXB9nuZ-AfFAgMG z-u(PH8Fym9bK30lCk-^6S7YhvuTy6+!d(OSK?>=`pYI?cWiN_-iHx z!rtN)f+!>5K~76<)hnJQtE;J^vjH#EVcx53PBO^H3iV~h^kxqQ1<5+;-e$FR_ge5! zBua@yx1~m+)2;=shi4VQf?nHRNCG^$Y0sHKw-)9Q9w$|NdwfUjsDgR+c=A)z#IS*> zqR=a!BD)-6LC*;?t}^HDCLlK39}WVXh|~`sx-58V96LRT>Ct6Wo!yIWt5Nq}N8kS) zw$dr+#KVhS*UML$54W*iz0B{dLs>h_!KyV_>-i2?!*Jq&9io4Gea|3>5J5yjj8OEQ z2ljsTmUY!jy;{-3f{lN9h__M|)LUKuj7xP7qA=Uy+_Zm(;+sO#Z?Or0e$wZxgdLq`d-D1?Hw;K7gokw;wOmRS^82ntkpm%f)i@TPqAEGYJk7;O2|Z-C<%r+O zCQ5Y%lvJOzAI;*(A)QBNtlchT_cUM1C@8kLW`Ig$(pEmv=!89w+tDyeBfVrbrEgk$ z1un5G4%UM*HZsz5^q?xObW(+gD*!P?e0r>{q^jDPAyFHi<);PCQllmZsa|mgI7>Gp zvzBLk)4Ko4NUz{$t$o}SYopU_QS`p9c$yZ}QEtkPn}qx1R<3@}5t?UZI*jb>(&2rq ze6rUZA+i+&JYsv$7IM!@sGQC+}6@opapbK$&lFWIB15m5k=9u1s-!){z|x*6sts z@%FW~2a~ zoUeyxNgGe-gYAnGiq286bFZI5w<*!1TO76Ld>j7f@32|7xRs8qV>1(iwVzYrXS2`M4en_&cFB3T?x)(z8s>u>qz~)c`x69p~w=Qzh zk0aK_o9fI5vK8;@icJEH$T|tosK~~P-5(JWPYJeoEy`otN`G+oC|)y>NU1IaW-_kO zkgIqX)XzFS#Y{1W(CnXd7484Lc9DX*Co8PY5thKjuDIN<7@AX{bIR>mR6_8ybTZ>z z*+{TebcXW853ny!&2spmF`^s+MN+ zA~=W(E>tYZh;CZe6eZ^CU%3fAl$^O(tG|J5`;t^VVh6lc;A2%~Ww^dH#@rEj{m&{4 z5J>pPo|whr2ylm2U180K#NJBvmT5g0e~u{$CBn<7q2!~LkKsgJQJQRb<{n+{;@2_N zBF>?3g>QRFGQh##`KVvYT&k9Y>sxn6`xgv~U53Yy4WCvn>-Leqe__6O#3wDbwhjM_ z;mqBBta*y{c6UE5(}aw}JoeXoJ}maJ@4d6jVR@?a9KQU#rm(E+=&pwyhy1SKZ(SRf z@8#T%P$w1&h+H=~I+G=qdSz?O3ng!}!c=CafM1wdTSy<#nFEr@iU*&~*c-8f9}@6A z2e6OQX?c<*B-)db$kNKnO61iB0s$PX_`_9T+7iz3hi_ zs2Q5VJ+B=B$qCPSy~; zcmo6%7v5*V!}i*X%KEPHWh{dx!CRA&l0uR8Ino>2JWY)E`mcUTA4+_A zi>fI_n56YtnGM9_`a-FQAGUYcMr*X>j&3<@=T`A> z!2%hHFZcWU`U;D;-pkXt8VPn6C_u$1D{n-!f7BE8^3|5mh`gBQ_OifaO_YW5@K}>tBs)UgS#>UZg$<^s8DJkjcyXURTz4`j3q?LX_ ztgZkD!up^ZPjo8>OWtr2;{|wdWoWUH3_MfFi*um$kLwFxg-hF(A0&RhB_0)UOJ~NT z>T>;9Fk;7;EVpSMgR_)^xZ!gB$`{<5i1r+p2Z z_cIjJTCUwue-b&BC^QKhMl*!aSXA&dTUCAWA7{KNDt1tCvV74_2Ae8?Fws2l_xDHdd0h*=p#*vo658 zm6HB(Ir47-gR@Y~_!N(U32V~86xm*M)Hz5}rERbR@C4=ZK6sNuVeC&vt^x5JO7zNY5j9?5+1-&&aZ z_(LEqjG#Pu|3^pIs}ab{Y;s>Hr%4P<|9z*z*~f{%MSXi~pV4?aL{b^+ZeCRJAOjjp z3Y`k25bj=31HL!A!?S|b!R7Xq9G(HFnv9v?+mbB79CYv`3-!FuN#anzSU!Fz{q6U6 zRT(8hhKRTf-_^1lsvlK~PnHMQ!p=5MxLyemZA)b%;my_8W6l_&&FVt=2iO*r2Q#{c zco1pQI8Oblhm3x!d5xnBS0Lbh7F>OnfmAlgOwdAIPr9cL$7GvG6M!YDeE|IJA(I8l z#C?AAle}c%4H;dS0#4GxjY@uT0C>oeIma|y;fD*Hv5UDHHhQM!?w_%Vrv!~c;^qoe zWY$T)Dg1u+C!g7iHGOuNj-E@ejq>0Bi<_;P*SYvC3^T9}3l(!qypGV1=KMUJT$VeTj zQMY?@wu~y=L66j=Mvkr5Y|W*y+8?H;3Aq%YANBAN1XREhk$Vf;9~@wErcLXt4x7i} zZECASmmq}g)RF*F(tfBb+L$Bh9~t4dW#DY2@dcEN=MLg}C!o9Wuw)R*x6qoYJy~&ypeoMWiwFdJC^z>+%_p*6- z>#sR#9+DGc#k~TL{^5|>XVo}b_~va~hMcOsGK`V8Vh2{_$X_+t(&?0R8^I`({!yiE z%abyU|5=r2qjC9(x1fZ$+Ve^Z!)r-X2zB4%@7V>EfsijR0oSJeX|3E#Cl7&HwTX`? z1WtQ!Aln`)=Dxn(zg^j>h0TnSJU&Z1Dm1Lw);~0ZNzs(|2Bu&%ztUMhu@Kgo#tlIJ0tjV;({1m3tN|eKQ z@Guq1w%J(FZ`0QBdQ4W|t5J?S0x3Qv)mwg)=9DFRxf|TJ0?A<%%xPE3wb%wlZeR<= zauODB^%Ln&Xe)DCOY~PLB_+U-9`H)MzV>Y?cJ324ps*6qT%6jjbK4*~M=@G|Vk^6H zOCEaDfwR+*GYbjNidUK;gP(FB6jru@4}jc1lSL{t8-tNDq!d-ZpvU+{ z5_iH`L-uz?k8$-as!*{JCcJ^S2F$_k(Gdvb+UUh_We%iG_NAkCG+yX=-UH{8Ja142 z341Z>&kDF&=cSINS^y}Esm3!I*Y@WKs|((MK!9kISkiCEnOf2hM+zKv9k{--A7q?_ z(BoV8H^idb%GvE#pi(aD#vMs}KqOjG+FBLR1vot?*}W%r>s`vs$-FPG;mun+03D*G zA1KaBD`ZS&;OF+u(02e>4SAs8Dvu2Q?0BN%)>tJvxu$LbVqTNFy3L?O+*DjjT98_g) za#tPL-auQ6H}!)KP4A2^n0(i_q5L^kyq5%$gU=WGrp9lS^{GCjZyEb$lqsft-blgp7{# z!(QpM*9Rx|&XpP3Z*UCsv}}JrXT$Ev&oL}>6Q{@!-#uQ_O#Ma)n!#1cF=AvyTC~>C zE%E&C?!2|a6Mj@B#s6SGGA<*vfK1GsZ_Po()2XA$K>M+M5+?O(TX0@`hD=JwA&z}M zdeumv_LG`$kMRyRU``u3Ug9|@3Um|3BEn*~a309F(p1s$l9)<0#C zwhNC`xRMpyJDIRykEM@~P{nO;7mR{#3=ozc3)K)u?s9DN_R(n)nN-?Nc~6sH>9uH{ zsLupCV-5(SoijY{qOs+96#H>~icn3gbA9@ydpZnQ6D70(*gj$Dq$JqA+Kpmxl;3nL z8MFBt18Q&K?>roxoK%ch-Kgu!8cRD=pcxvKYMcm-wb7c5?=Tjurwixqwkssz0vX6`N88 zb-TfGM3U0LG|5RD;e+$y)HX*1TK(1Fk@ zsd(ls2cm}}j&S`Y3KbO<0m`WRouJ2%B6C%E!NpD7ErHHz&x+h$u1;Nr`IxUm@EPw^ zl6Pl`BLS*dr}*e#bw&EN`y&JG?*x!ZJi^_#fbPi2F3SMtV?)%R9=)3igQ;x)##TM) z@7^D{@x)rd$E-sxhwg5l%)?wt0bj4x!k^mmf>jEM39IvIvI1SZp}KjvG?1C7Mq~w7w<@r7d%kUEN+5TZ3Bav-zJU|3_Kx|b(W!z*}6M3KU?mDZ;UI8*=VdqFL=XuT6 zgioQ?s;8lJWY%kzYTegg2@f`GvCixKR3u>Yb|CZMyOh4EmVyae$m7{JAfF|_o8T!j z9`NFGYd2kp+`S-ZDJ_dCY^YBvuVJ#%qE zTL^=Vr^H~ZXjjy);A^zoQFWn<} zEk)Lz@bVi^fzA`bYmbouRy@+HU%5MzMA=<*SW2OFc!z_w~Pp8|C_ z5{V&~ES`FLtS(O%qLRQJbc7%>55^T1Dj+78e7CpfnRu{jD%2tpGqv06X74VaAppu2 zhL%VJU`t^hfY~S5wF(eyu;aOoXmIt+< z&0Bu6V+LC17&~jvFg}CJkT;frfySM_D2JpT4MxqJ!3V|E3kFM2h+HVHFi1)g-WLrS zy`=c!cJ8F#&^%NQX`d|UwJrp*Mk{%Os@&;%iO%Ji?whlVFu%>~CE1?Xm@f!k>Nr`# z{=M`W$MF~pOb4&j39}8i&ul&a*`~c*X-FpV=y=%L*k8IV;e$$xJxO&L7foMAXH|~) zF*wlY=m@;xJ?!4krKYFn-ln_`=(YR7I4?ORp&2eRNZcQ+A%Q=?hWX-!c<5TK$B*Mq zoa0{4yTV|TArZ91n|U-b)}q6e3>sDa&d(0wrOcronA5~^e_2xFJPn`SL3vA7oP1;k zy-m>1^`P$_81QfPgxy{~CFSKY+xJlDt1A_}W3&0dc%Vp=wR*V)>`l8#hy^jd+Cq{-I~56_RxEWBxC zNlX=;&(FOEg+d5?t^-q)s33d(GJaVJ_f9*<4-;@xjugZ+0U+&YT*_driS?i^FQd2P z(WKDufZ3Clqk)ye=&UyOyw=7opZdoH)WVD=Ahg6!TL@>9UYwBhcbL@C?pxg~9fcix zjg=YMNv4wYt77)%TE_g9q}6mAe5VdZ%G11Iz~p?J<=GU8+5B4d?tch+@=Ls+R%{K- z#mve|uDn+&`wLKA;4%IkK{WQS(N4?U2+2iVxh0+p@@yd(zz)`5mGwC-Xde#fblpDG zJ;6-27M~uboF6Z>o)!0u(Vic$sHCes&+g4y@RtjeFy z7t%J<*?Y#0aK*e$PCPn9cl5p0ZD0urTwN(3BPFX{=pQZ&_&G=-6ieZI1@a4N!&iwa zIrd2&ST-mnbr0dxEg##fOixd@0Gqe_-{wJ^YxZO2`si^a&7QlekKJtHIk77$#wOz| zXV-@`2hKKXVKY^x=L_Zx2AWp~@bU36xDC%Zdd5JOREO+WmQz3II;NFeivm|r)Shp) zEYqF{&K_^hHXRP76IRVJoT&eC4Wi?)#*nZGBPSRTO8#K}+cAL-FC&QmvTrJr49uu%%)s$|V_t*f zDkpYFU%m&%80*X;SVKm|SU5vAr3-NNK}uNlk{wqvgV{~3Qk@fo6ycMk6b=FR4ND%1 zAk5UJU`VvKKcUBWk%4c&KB^R5pZcZiA*e{bm{O1M^>1{G5BVD1K zAoO+g^YsNPaa_*bb=vjA=bHwz-7~6AkS1{ROP0N_Nj+}WD2r6z6t(*7F$SuQ^o~w} zl+n72(5_5uD$!K&uhmCp{>G)u0C)75eg4pG!R&wk6;0kNvdkR>s6&Q8?g?Wel)##@ zBxI1yMLNZ+Z-_#q&|sk#3AxCd|M&kA)|atYfp~_QKI^ux1(q2EKl4yPz5;83zD4Mv z3yR5~aai%Bgd3~jicw-wG}yDxUjbdeg zTmI$W2CrBz+;(kkJ z7F$5dVP452%ho1p#F`8BOQZjYcAEEz(=!kFq*IL1_t1;QB>h{j zmcgScN^(hF-s^y1*kyST0=nFiEDI6xu&!cIFe)FCp^!f;+wqKp^h}5ayy2!2wErGd zc8JC8S(VAD3W3lKyOMh&pd9INXBl|3(3Gcu4akxRCams(NSvSse20EaI=32$*$Sks zP`iOG^^P3Oy4}D65;8s~-^f~irgV#J*0q`7D_<0`L7u?Dp*V3j$pJJAO z;+hV9E-2q&K@7%N?X9#%tyJN)A?&Nep`D=KdHT^=31Sx zwZh;xi%Za?+NwA5{a1yf}o@R@?6!u)qsQPt=aa|{cDL= zxLZ#v9h&@zyt8jtj`u9OaV2YBcP|(a|IeP7&aTHrXX$1jl%D+EFHpbCRB>BaG(;!x zEDawfKpWs8=3>%}nB_kE9&~vqaA{HZtno!n`dOxPn*6~m97zP?Sn&Ho{$izXSU3c8 zc8!*Yt{Zz8tsUsmUTSn63AhcXwC5eO+H;eto)KB9+N$yrOy_5vu9yQ*ba?QMd3*UQ zkQMeT9bdksXj4n_-gOmm`T1q0+0O)>acu1fHb{4#Sn>ovJ4XgN>*E#ET5O%kepL=x z*<7HxJsXs3uqi5yB^bev{0hLgTA0(`cg_#)x~7r$h7++|7TKi*$4IS%HN@!zFFTAz z@_akP#7AJ_+~suOT$DSe)$d3<2poA2=6F}5WVj&lKkM?)Wlyy%A}h#cx1d*UN{e2G zgzo{5IjN-I#Ycj62R+>p;1qpCjdW*b>~H--(NDYWP=MGEJCiRj)Gj0(8);PVy^cLm z3YfOD_i#H^JZPjI6sQc{F2D){Nhaq@A*e);8Ba12Nljcaj(=nSsc`nP?Sx4K+nP`B z^iUR=0gUE6nPg*GTDQeVdE~wX)q%I$Y`{S$rKI~g1?hi-V&wqJ9FMVrAaT8`M^Y_C zLVue^62VWOoY-VHSu_90mLkD$nvekvbPDuw9d!*ad6RKp-DJNjag1)LU(A#^3`I@; zThT`b8@%ksI40dvoyF+{*>T&lf4VdOe6DvjS}g2C7~xyi5G%7_6)AeO*=IB>IZ)t2 z+>f4g9#5cW8P*4<(};5LsL!9wb3}}=EV9*qSr-%tG%( zx<0;5^y&892kw%6BihN9L-~c*jfEYb`gXoM>q*4=_}QTk-8eXdqd|Y^NrzzCY9BR_Bz2J?SK6QV z;Vi?d%-Ln{ZCC7-{;KFRin6m(%rq*=Nql(qYDGkxcXE_ zgR0_33;A2qt^WSnNk5stQrlWgkeGiE^NFq)JDxMum-`HMfZ zW@!NxFBYv?0{`?%oKaG2Q7mMXBVcW`)KKRhU&!cP>%hR7mf1b7VZ#P|) z-bpmR$zj-X%O7RGhbVZ{??kzC%&njwx%x?4DyPe{XPeDwnSnhCif-M#uXjp!MZv3~ z|907w>7k`9Y&mi0y$00rSg_z;&mzwlu}ux0?~50821QwSz45a9GM%fzov}fcj zMwz#q>Wv|okNm|CZKQ}ZJb7%svZ1BJ2-L4$7_=`Df&v1g@hzkTz0{J|-b-9z1C##l z?Bep^#g@ZFHS4bN+A~M)R~S^d2_tH&FD;WsWZ$<`$2^+99b-U}IWsf!bBy+%P3b@A zE}h&m(Tgw&JlP6T8FFanpgo7v@SDxg&%c(+RxHkHN2AfFr=q;HYT1O<9WQ^)h0)Hm z2Av0scx}xz2c8|PM4xVrT7Omm>@VoyUbc0mfll^PXEg)GJoIr2GEOeWRFN73?UW{c|u3TYmPaNCx zZEoxz6i*iLUCP89b;Sg3gAKAuIWOPhFg}WX3RmL!%J+J-SC4ip`^X(6EwP5SLc{RH z;HjQmg>o&z_m6 z)NYEI`iEvqh?B()k5#$P@aJQ}6;b!hftHV~?QK&V1*Ec)NP!dYanj{c2k=1rFyYp} z1?jw*ZxufHzM~l_jRTNOWV;-aUCs|b8~?S`@8Hn&e{N0ZP4cY&N%(RB<}~@dT`e~X zOmciRJZn+|7l1%edXjUWjAHFK?(rGBq9FrzNssSvD`md;byTQGyDiD%iM2aAs?h0Y z#&o-1zB~pUS>HTT31a>R1y9i6%N9Zyc1*g!-#@7hoz|!G$X3G@H$Yw#6@V|Ye}T7- z@P`B*_0>{DRfCC97-$oErP=f?jx-It2AT(;1&Z@bs!7#uIgHh^-f zhL8W&gRy{%8tVs1{`mm*FMmujhC#={|NV2*btiSW+V_czM%b!8u9Y$WMLSu=&8JI~ z%pooNwZd28*#2&BgGOOj#-a~wMji+ssGo7U_X+DY{Om<4#k?WBM{pA9ve!xiDQ>>O zpm0&C9qD}Se}=^$W>JC$th6!VFlzrb%4oNGDt#8w2M;PPf7I8+<>X#aO2MI)W&UtI z)3M%=>x0yP5_`!VwARTSB919`FZSo_&y;9&nr?t4z+Fr?aVM7lbkbUzVUJju7MpL? z4FUohVGmIFrmUnC86E93Rj00rc9O97(E*iNK$W2A$Egy|GfjH==}Mw0fjrj_HYUkZ z{~M}dx}er6?Nl!bNZ*e?My}cTK(w4CfRoBVld$?eF`klh7ASW@-28at{(A=1OV;@)UGaL%&%`swuEG1oGGfCBs6mU{ zBi(;)c6x2s8DlDstSp(xu4tQdipi>Vp5>CLb(-$^`%PDs3}MUJE#G8iW##vWbYdWL z7H@sB;;6HFaBn~7KNG)UEOKUV0u9)3-Ww4j28Algh|*j(bapnK)uY>#l52f|r-y$` zp#g`#pL1$hqGNHC(?E;HgAmw<56Hyrt@pP7A|JFDQ2pPsNN^hU;W_H1I<*d{Az=QZ zfm6Lkf_F7v5c&3P)w5L9x0BFOaHtOtB44TK)JJ#J1}jAD@qF~N-+&}Ep4 zq7VE3S}9`o_%ruk+50>OaTku75pdP#H^_mtJEip9asUzzTym@bGy@upd|y5i@mhbI zDg`bxeD^yCQ~D?1>~E(M1Z|f&)3AZawDj57EvHD?%_WxPt$3V(#MK9FGtB`wI5-Q~ zYWJ^Mr{Ic7_2xtcCd~>w=!*Yjqj$NvN)L3nd&vi;)Z|uQqI!swF#Q+*d%(fLyUKtj z%U6BCvjYAj4=IV{JAkR!AMc3{yq6Fx!EJ!Pde6!@Z0_QM6ysFJbBw=EvG;r6QHc1T ze!uPWU~3Z}h9l-g_v8-irQUNU=9p$r%N6|!RG&d@OuFHNJ_{m~Dip7E=sE9aGTSW9 zu!!O9;&okPM0St8kOS=E@;9Wd%K6f*ueZESFrzVGX#jOnxXU0v8kZ*{7Eh_cQfg`k z2M1~H_3v*?#w)3$xB**Av&AD}$tFyLZG2^>S0R_21vkVJWNs{e`z7y%C?0dRaauR% zH#X#RG-I&oOUYwD(>CVY>=4zuFfBQ6C>|4ja@`q$gYqDUa;a*Vmt@b7df8 zry4EMb3fi)@lyWD!C*tgtV-j@?gK5&{_ODSYIl^#QN=zlkIxUMLU_-1(o%<%H=kCz zfIXFmyQ9zkua90Mb$8`Y_OD{?D*851F5IXr?tr@QKXXB{zU!GE1F-dA+6?jXi{}t| z6|Si!PZ1v|r_!OrlUw>J{+27LWrN5^;{~Kf2-O2FE{?!lR2|0mSH^*oZ1uX4@c>K+ z;ecJmOM>0)H0Ra_0aD55heNF&#+Hj{c^1RabHNzQkJw`IYbD3UOrK+pH>ZrYty4*w7&Q zU5Tm>I>)@y{yx#7cAs%dw%%}586XcwVG45c3U||ior{WA3#bNXFbx&eR7*hPCPEHx znsl06(!NMkoOgN6{nMij#ccj$FL`9D6+)HyVzM40^k|2FiVP42xVln-slIjlsHq7M zN{HEFDF-N`#Em_OIP=@0s|-ZK)*W zeyaZD>tXE3FE?eOr3>@tNF)*f2!)`}Fo00E%s}1%6sj01Jbo>Q1jQ^n)&n~LF4Y?* z;V_dpDB_)=b7JhApW+sj=i1< ziVQ^Mz@mw#v}>`@pm*w~Yz- zlDb-{jxq=af&_#rP9V8@;+d+4OcP~BjmIY^c>xYSyoA-}Up!qb7y|}2Zr&Auw(_8p za3>Z9)b|F|qtgvz18jw=2Tx=fE@%F zF6)E>)9(BUl=c4{69i}Iy8HaIe57!VWwY^Ehx$`d;%GRS-$ z&XHRutg^@@UFCW~#|cIW?~RG}?>NA@D?7!|N;q9OVkM>OH9FIl5xkjt$^0&%!^QW7 z??Jamz}`R$LA+>!=zyZe)#=&UR`=!pg=x^v(}!2uCfN3g-E;FO;swlS3jA?aR+kmsrv=z|+V z*N8%aRu(!%IXcitwusilPxW5F$o%M+RCz79udDVftUgsq#}&4N1hm=ctZG-$?q!fl z+D}(-BeQTxhE3$<wg-s+C9W z)5d!)?tXtvMi-(}RaNy*HLC}X_tv^IFOg76f*TL?P-A0cp7G2v7Sl>8u5n6}jJ5jl z4$A}i3PPYI_Fjkp zmr0ALgv7a%utr4IhEck(XHSCKW#F9_X$I|lWD-dTZ-ovDq;@rL?@7KcWLM zRHso`oh~65H^P=Sy|{DqYB{c=PQOzp@J$PQ467#9jNFiQ96n3Iy|LqWCa1qZTk&K^ zGorhPO7U==U)TB^a|ZAq=rM~89Xr)K{^NTUv&z~|6zt%O@=}&gmAC4k)j_)hRq}Rs-!H|pWt|?`CE5;Z9$eqEpwDM`d^78U*6fZwN$ZM+FpS*uhC|?^8 z5HPV0cC(=aI;O5y+x@A%CE$danOT7lG$lDK)^LXiJZv#1x*5g4#3>tp#SgTOn$gz# zCT`IGw#3!||8KF6(h+*JDFnn5)1(bk1}4JNqw~p+>-X>)+|`qz<4u4bTDbNp7?IuNm(U9J_E#C9tmvr7N8h< z!Q+I^A8Of_xuOPoQO-~2O>YT0Ps7CANBQoih*C~)B&3H#RE zTwYxaQqkXOr1dP6UbtZ!h#ymmW9%~|yC49VK9q+#{*rIoX#&n<=IaOH8AfeX_s**6 z`E>>)X@WxDC!Q5keHf$cn81+ZdKrI-7x9Y|4KrR!z!-^jeU_b%ve+B4axrV|kDXDP zt|L5dmyE;p^|x}`@72@egSLQ4P>W9@7CzTvTCclrYS{3iM7=WCH2gEYz@o3+oC=KAn}ywK;TK+Js2n}KhN zx}V_f((7tFoK#7axX1;^$F5HL{P|rae_hm>#6@h4bg-)#}2&no7Y#s!6}ucc~vUUrg)WJ{fmBKz?F8GZ9IN{ zd*>3Wj-G4FMj#_wYI+gsjRA#y)sesyG}p@Cnzcuq`!Zn?{qdH zX!`4XtD^p7HjU>?I^hUi^KL6_C>iWQ7W@1$Mn_57?ZQuRc)h}Dp zs>m%M!%e*X*5-_9$*SI&4QiycR82^jKUrPTj6M1sK9&2^W1lTLCE$Ba0_N>}*8wu1 zwG^dzbVQHCF?~bJs)fUR+&uZps3p++U_!qjUqIIuHagz=b7#TlAIj{9dg-VF71pt7 z&>48ITS}%(w^}L?69dClHyA+2YB{#gN#lBmQWj|`DYJ*V`k<@IH(Yw3wE{D~Uiyy@ z9k&OE6w5?7Ik7XEwIhY#i0IxmYY-+j^)G;I%#RT?4(3SJ?5jVg1E-w{_lTyox6Rv06h45v4Xo%E5LUaa`i9Tq| zEb&O>eeKL2%A9W_C!lT1u%N-ikMbTprl)mkE)UVrid$9CI2MVClxIgOFak-q#o7;5z)-gpq-}R9Wh>4e zB<0)d(K~8$*&~&I{2j?NlYDXs4h=>X)A=2;sft})U1q zZ7-;^(5>DrmF)RkvaLZ!sgvcos$1@^9D9Pum2fPB@)egEqLcYO1~HO?St+8cpO1}? zFZTmBiHAH;dN|w^?3(Y?b)2^eahWi#n~u;bP_=XhBRwO1cHanOk8f z#0)^-B!CTh?+Cx#hwXI%zVPt=BVk0>0uN76owl9Prb@*)FR8P9ok6iiOyYUR=zmzlgqg#tFWBzjTSIyTN@;Y5wQ}7?B7s&*8we zq=hPEmyu*u*XqD0W4;VX1$x=mj~@1zQs_ z=+_!K)O8(uuph(*|Kle~s|dQ<`j4_OGeb6xeXA^>p+`hStgtmygBt0=f&!i(uZWi3 z&eb6_ZZ+IB!Gq0E?4pgn57nNBnuHNRrJCxBa!+`?JY1*@REUe`84eSbpSL+>F;4yv z7eP%Ytw5;B}^O%&R>w&q^bbR8&A5^AQ zHQ`;Yl73I(E9k$pVv=LmRD=sK;{pLMKyt*&`17C2+FSHs0x~gl)?1mv2`SIS+{A>+ zM|jJmW6prx+RW6iaJtShF(-Si)64Rnk#tyfa}w>nQHxK-QHGSyc9-5Qj<(qQr@u!% z1J|+bW%Qe5tZDr3s({NHK56-Vazan6)*zKGet~qjCY1p^o|?>MJmrcBqNN#tHrCNk z{*~6iB0qlgvIf_d>LTGdSLh!|Lj^4Jw>so{S61I5=nUEMyrKVXr`hzOH7@h{+dM_j zD!AG>BE-X@WU4)jjX^d%#G>%y8}xVZXpRG3y2%)I?&4#htxu~(%*@ZsM?fL!yj8UJ)h7<5P(K;CeIq;~VZ?d9< z1fpC4jfA)~|3r5L`|Zfcus!4wmWMD{kViWVpW;qz)~OB=cx$f`C4|oP;h8j{APCRs znR=Dfie}PjyJtF7{I$4%b3aMcxFt~HJf(B@U+t!ETbU5|^Fx(VMOmUvXI0A+9u#N@ zoqiA|p1E7QH<6H|lu*P+^!K+6W=U|zBM9*8h4FHd_@oek1AYGsP%wU$O$TdTvpDM$ zA>T#Le;WV2>+ej3-Ex0c*d8E(zu+;wc4$jl-dC{GD;@QBP6EKA-XVKUpyQhg$|H)X zfS%^_%~G#r`yU5pRYbLKia}3H=Zmn3CU0klfZFh7MT}1C{4mt>N$t5fUhv#+>9-4* zZXx6d25zi#*+Y27w>u&{9g$1?u|g5pJ#KO79W}{Y+A9OK(Wt_{q?+0|Gw~0mCwWC3WtwgJ5v*1620>W8a=m;#>2vpXTN{@rZ7SeP(W4Z zDBEqLn)ho!`W0Z;a*&x5(2Ioe%3-j3$&^ZdkLi3dOy62Z^E3BnO-0N0_+UOw#k0RC z;*KrYQ(VbnNV9I&tgYvx6;pIyo%FiMqS9+4#B&!W#>f;7MxN#jZQVXc)e)T5+5vzV zJfq+Akqd#ZKfVLiAZ4;kZtHUl^z?Zov}nCT(tsFTQaajvm z6xj+q<0jOXbENzSJ>U7maVL8rwPap4nBp@q6!#=mBf660I?H&dE6q86E_@CVVS57+ z9R*Zk{=o7Je}>)HFkbojTKkmA5@djD9?<3tt+@%D*^YG+_z7+HCMMFPaD%#Tx9=-= zl82M@?Xh|E0Bw3Z-#Wy%Y-K*lEn7)0ZBCZ9liG^jbRZ>k zldtX0x3z^`>c;e`X0vs}O+R`#X{Aruc7IOgbF>gtrVy)-7b-Hwe7yb*kcziIuJzzH zW!jKLcwHSXEST7XoF=bM;O!(FEt40iPGX}7PEJb7LdX3lPi5wqsq)HIL4;IA)a$Tr z%1L{%#eR&S4Ez+0R*4SX5S9(AChqc*Rr@-ZPK$j6m_$HPeC(;1IT&aJh&CqsUk(xc zTd^~h=2ogY^PhVk@0J3{`9#{L-a62`=P4^5#44cr%>7G=qgP=;pT@r3ch6cqjPQ2i zIKvD%tES88XB`tS0s;dA&CK#fN{Wk_CMBQT9phCNz4F-B?Sa)c|0Xo{R~;M)-H&M& zvAeU9Y6(7pb|9?W2-%^PMRH6AT0@9_t1iI!Q|2;%=Xl-gZ)CC&VyQd3H%jF*juhK^ zIZ2z>duV+jr35m{!r)y!zF+u~*3Xp&zV01#5N7tpr^YK>6e-+oxN_iGazEW)tceis z78|T7F5f=)(RTqZo`3f0y5QPSj&Z${p>m%d{}XSd9d3U9o_r(?8ze_&&)fT?{Os&Z zy-*3rRE~4aljOg9Y4Ymp#|LxfYg6mf`*IYmwzk;bk~tb1=hURYXB*rLo8zupGw3Jb z*ZyZKDfPgFt7QCuxyA*o%6YhqpN){un5~=r9w;oF54yQ({5{*`Jv2DjH%CZ7FxC3| z&6_s_?DdGtvtSg8I3@;M<;DcrqH&&oD~**2BU{HJekVuoE5gj}nV~0Fx`LJIfN0h0 z^50+hywCz?^4K>Tmi`L-T7-Tf46IgsM*hD#vzVnu=gXfkO zJIk%E7!Cg&*>G#$2z|0itx`G)#L8nQB%jjBOIKvTkqd(K3t$YXb&nSjCuU* zxXipBIf_>Hr*H_Ju%}2=jQ?8do^JIPplNU!z?1>aDAasz^-VhhM^PZt11&``ZVYES z*kxrVA0!Jl_Z*shw(9sYgin$`Gyq^!nzEy3gG9gl0Ec6 zT7PATi;tGN#4`r+SvxaoLhp_N={}GxK$>nRH}s?Z2n)T+)L6_r*tcVVoMxL{SG$V$ zq>-bgj6}NMas_g47Bqr!n*2x?B0A%=I02Y>th*$z|CcGq6iB#Nc`9vt``_1^6_lF( z_!^(1K|+z~Xc)f>H2Qc7d9nRAy0Y{qlzU#Cm4l%MQfTwE?rc0O{Y z^m97N$d+pjHvr0}^*%w`+s0M{_UXU2SHbA;#@x=TD%p<@-hB2~i%gqk%CmYOL$V6e zu)|&es7So42a5WpHQ9ZFeMdYgbJ7y6()A+hl+`}Y$!M8ZI39hpJ0Gw_HjxLeHj`jR zfL4K4?|bnwyO7v~J!SY3w9?~pk^#!iSOY_%B5=8M6#b*%uJe#Q2nQRbwpdIrR2V>| z*8Igv_%q$}k%OtCK~hjfkE5p)+}O;Lv1KofM6UnwL&C^}{C!;MeqUX%!5#jAb%1*% zT^{O@0#B$AcIY(YoJhEZ)39M1wk>cKD7MgjU^R?n&cQ4%8+-SI6+rS&OO}tSl8%hdg zK}r(PPbk(8Qa}baIA#=Tqh&vn%5Popg%`JIkvkLr7+jt+{ISBW^Td3d0QXbR^7jS( zm?>>fAhi;F{;MfqPlba&9v~y|ck&u2lV@ton7)=dsTnjJ=Os15mj>?Q~-5Ww2*_wA#s1H$p#*a{I{@aLxXAd%KB zBVg7ZG<-Yd1>~1>WkKdr+}%boq!#qsceMpwx5WSTu0YxBS7dIw=;MaR@a^4Pcj&kI zH=XY6r5b<>qEU#9gv86^wD1u@&{amY=;e3i_i3_qphaiL{S)E68}i=zHudYXOtRdH zAc2LwfVQKvA<>cnz*}})S1G(eyb6IQvtAflxIDS@YLNPozb=$>3Bc8}wFQu=sFKDE zeG7XKTQynx7^>8J@NgvBQVPK~K5_rmt#?SL3%h1p#_M;>UP=Pb^~JnseDW?{V=<=W z*_t~E9s?SieEv<7_vA9L$1T4!d!&=TK@S`@?-9gcp2*VW0*((CK(@@Z^OHLYc095z zi7D|cU+^9lF^VlL>1Cq~!^bXvqp_j3&yvru4|@skka**o&(l-^30Q-!JU6TiTrMYa zK4x3olfTxr!0zLJoBsxuVxES)*#&A&Rz|=m|46z^sDe2|{kwglIr6Q&VD9vtmlrVR z^df@JO@NI?t$5i+ixJPGZT=#ViO(N%$2cY$Et&7JO?xgW(7G7RM3edGh{Q7Jc)}2; zkC{!!_&~nT-nxu*M~iv@Z3j;;dq3TDs=?!l(z~F0HEL7BZY%Tj0SOtrQ&xakyU1bl zDMx$H`onQu6o9pisMqB>Z=%x;ZCuc9(+7KgJx64=a;gcbGa?mpdeee~aB5}(^ z(YE9MdVT%@(SXXLjFf)MRh<%GK#D+z#7ITo*Ul+cKH4%N#Nirmrzm?M4w9lpD3aHtNqr6StIDd&Xq4y?A({v|im6p0 zFO>!NsGPYV7aBI1vW0e(e4LO__N zr==|l-UALXzO%!wXi|VXfq^1dA_8!tDQV*Np1&Ri9pU<|{BFGo((2PcXw)i|UDG?= zlz%0GyM(}8(H_nvaI=qS{ki!&D2SS;aRiqm@It8dn11p^So!>&1n*TpiDGU5Q$2<3 zla=s{-W-sRbKp9gnTgXc0wGdD9jLKoR=Je-cP6ydjn81#-F2!#g=F7sZ>8M$GUqB$ z^zaA$syUGSG!V~Mhgwmm*dwa#=b)1xl{--Ny17lizjVOo(bTyEkY3$$kq~AZe0}pr zu+r%0=wpCX@4HJQ#6BmtZ{q#cI~#0=3yOqf?oW*EsvFl`-mYA|MS}q*fqVpgS1x&9 zcCGPzylVZ z*J8N31FAO@Vr_xf)nuW}w1UGPW3{GH>cs4s_-2II<4L;fS()_8< zvH6YmXRmBG>sN|AkSy|>l)aH0`;v~wLy+aFb^qG_U zgoPuakM{QaV|$B4&&rPCPDw`6GrkwzQ3`H-F;5?)ohI8Ob^D@J*gkyx&DT_@YX(QS zXO3tnYsGc_$+x~$izds!*Qehyd0hxhIG?T~#jFSooTjk$!)!^%KJMMYJJ0uRg~L+0Ig8B(GM8s}45zJ{7(6SxJ{*mjmZu0--7n2B_;a5( zhy8`An9- zMdjts*X5DF&Lvz2Xna?9TP~tvdbAQ~gg!?0z5<$F5K0#Ha36ky&(mD5jwv6K^?gdv z?p+k^S!1R$7P4ch^CX$!K8h8txD3CFn01P=!~8fia=_*ib9W*Z4kju#-s-nBcfY@T z=**u&0Oa~9M4=vRO32Z;c3;9Vs#ys*j2u#8@4wHZerak0-Yp=@XKnV2@r3^XO;=zR z{6cGF!$z~hSb%!* zL)OF8N6X!~A%b$#CFBC$xj#QRBJbEn#i)zX&`!f)SEEw_x-GUZx&|m@gEShH-a)mD z+4Sp^5)-i!&~8^jbenvM3QJrt>GS8$x*Lfw(?DcLm*Y|GVNu+BnGg~$@9%k%j2F;@c$u5Gc2_plsKVs) zaW1QuFIYm)c;065`#^SzN$(j(zJ~7Z7@F~9oT@s{_^%1gbF$AGUrdc}r}{A4h_~;> z=BT>%Ghf#cBe(btzgBIRy<}Xs!t;>NgK3WE#kocfi!Z1mN(eoF%b-$IKS$0oEP|m? zXAOWtz!qSs3E7BCfR1@nN5`5cqHf@1LVWG)AmY3^Ljbb^`xJZ1V!k5^5w1|zX_ogR zAxa$L-~s3|jPn{|kFA`w8?^BGaE)UEfAd$(dRA_0KSvDJDPJJUk_C<^a8eHNq@{6P zjlhx8?sp+)LejCwWi;@ErlX+Oqw*E~(n1;&?Q>zF#)>Tj)N1XE;i1N0vA6g2IgfXKQWsv5L%8D zP>l@nL`6RhsPuJ2P?C!U%jN&9K)6h`w8+1;r}=j>~ScOMEgw>Hndp@R$dDko8&_2 zU!a_8OFn!GhiS%KmPbY3EY6UTQqFLfyq#={tDu!m;OVl_A>)jsveVzeY;#4;DDBF8 z_LNOz6y6GdT>;ZHtucPO__4vm0PPG6&eEj+DtIy!oWFlhssys4OvW$9bpj}CYz?KJ zw`TPEK0L17>(u@uB;Q{{*fEjw8`rBkocR`S${m}j+oP;bscktsk}y*H(3(y@`n`Bq zh6bW=NKtyH0}iv-_Na>2awhpsQv-ieH!8_KqdyFmZgp4`u#Y^O=(2xDbpJtPUlA_&SDuH*Iz}BC<*O>VbU0jyip&T1;c;R)r-f;Jc7YTLG@vd$L)NE$8Fz5 z=j58KcdYovjE3%%bacfx+RqBJYB{Y?Ae%bW8m-fx8racPM?Z5-19veeg1^ zD2AcgayzOZu$sYHI{F4S$-rCslzx0j7_bqZ;&%|SoKT)hgm%42ER5Tzcv1xg_}vSu zc8Y0Drvz*lLa=10)U-$mOzWc=Qrq5|U~GdOuFu0Zqw$Gso0vn5F3iiPm8I}&AdBHY zQa+EbRLdo7>}eY!2b}i2Z>yv*6kRGZ{cNKmmgoc%GA@Qe>E933h>6Lse2iqsX5C2Z zoqCr5YjB1YZxtP{J1uh{rT3nFg?yjfZkQBd&725`N|?annR4@H>oZEY=) z$>TGxZ;K-CyP*p^(8nci1@ zG@n%RPT++mv$3wzopD2A(iA?LzNxr8wL89KcPG3O?b0+6QufplmRLt9cZt+`6)FiY zOcv3g+cMM>93jkb1A0rPUjZZl@cMN|DTjOe@7P672rKfki3HrIr zbj;=t>S96vB(E?P#NZRF$*=RNW>q#377sy~j=Pl0?+{34{@1xjMGHoPobSi?GCoC) zoGw!Os@3>7q}ol6`?Z*5)v~#>>vL}d=H6AWZ{?=OvO7Uy0oFf`qHI}EBQR0xs2sLp%-cDp^QgMwK* z!BQtL58N7}FrvG*!3uKaXJwk${wwl^#$n08V2kKk@l~qd`zf|{Ca3UOR(Pyl_iM&C z%0b0UM_IWGNN6%l^jmyX%2ab3q!xJeEH5SoK_rr9a2>a(Ij-tZ5!%W7rE|Ah=Gi9o zx>|;yi|^Ma2m5chHN=NvvBBEE>ZQImz4JI>Z-S7tBvW(EA-l9Tm{7V#34}AsiOF-4 z-D85~sB|47N9Ag~_SbAMV(TM&#cdWw~`Zv8P7nP=ZjU68ACK`aHta&IOz$Cs)$ZA z*D=D4jSaC>SO4X*cNlw(eht}YmkWHo0Ft7SY?ry*1gp+UXqAov_Z&Xc4$qe#L}#06 z);Yu6Neam^{aTeU@JWjU(Ra1`0KUSRi$kdqijRlUrB%9p761wZsFWJqVfVO8Vc7Q^ z>*wQ=@!Wd~`9+sYKB8kTpVIk*KCGuuP@D3>tn~JIYBPG+T(~ z#`?r25P3(~(cB0lE;jAeSY8y_R?#?%OeJArjnBnSJ*af@c|xwHhB#*jXq>+ZRrLjv z4WsVYJN@_Ng>%Qzm_v_~DxywE1Bo`Li&+4?_2&(`hJvHI zenuJSfkZGRb>O`>YdsR8W52fY`s<6cwd`z)w3l4U7C2J6Hvbj8%#e3H-b6F6H}Xx( zls=87l2cEU)%P6B%W?rZQ#m1P(QKuYI%06KJknhQZf2HG%wG@=t&`82>~aXLe^;^n zWf8r+{!tEfdvvR{l9=Bh6FTgd0X+oVPq}4VZ-05TQ#>~eU&6jaPgI~t@MTcw)f4=q zg@uK(BU!|gHYndGped6^FVntPcV)IYTNn0jyC*yvOPH{ zTSU1+g71-hdvjumi&F(dV}8`tvK%1ld{o;-q=*OmCO*9l(8MlBZPNf}0T)YMOv0*5 zG`&l#%JA{Q@r0GY*VOxU(7GH~eww+R-4~th(vr>60@G2<>x^(C`~6_3v{>mI>JYee zA*nf$rx)Dnij|&Q=@q2Wfc?vzZ)x0XCmu4gVx{MrjE3;|%uo+zCFI%hafY-~t@4k^ z3o{MwS)YqkpECrWeh0#55{lB8Nt3u|fp)2;2<}=Fb!pDagF~uK@m!PfsOL6|07f&| zOaOqjKQxj%@M_$2pTE7`Hlz4Idm0Uo$BZh=2@*b*9IAwMNB3#+kGbPbMH=P^h~QmU zJP#;*DUExRWm`|Vf6S4$Kyf4_ijiSk15vm5wW^ME%oH*uAStGy^AQ&;ANxXM^!t?G z3e~5sr?mT#vU1JGWBQFKGPWFlvR=3QGcT8-Gp$1T@p+II5QwDwI84Aj`X2RR&8 z(XdK#)@1Veo)Wh>$iNr|fv4AwWgS#Xd~HLe`fz%ULNUT^Y7a{Epksn8tZn>1(H#IB zSnmOF<;Z{1fJ;6`13xux* zPOTeoUyGs~oveGKY9Iy{d~kC$RS`tQe&Hsequ;w-U7y9}K{2Bdcpf`)GPy3piciTE zBHrQElo)$br}TpwPnUG;pBf1MT$k3Pqoa51_b=)#dJ|6X5m%Lg>*PXwHC>vv8VD9P z<%Qz#hj&y5hJ-INvm0*O8QJftF7`1a{XWe8;A8Q7E?}?OPltnwlI{>(Ngy;m=OoSq zIAUW&n2Qt3DmJ)t=1ZtSgBu-YrieD!#Hc6?oQ-5!OoJ>#gTLwMh8YVYwT9Rx`d zSp?3-@B4jauWXgC%XZWpcQBC`-isS!=lGo0^`g_BH^>8(+M+Ni}O4Ii_j8<-6DNdDZXA~i9FcA7iz2ekC6ORIO=I?u`P;d^kuh&CGO#R-!Z zTWam`@q<%F7R^eMQ*nhL6~V%U_L|+b&S`B@jm4%X=+HKlz%E%OsMECu;bq*&uly4C z5DimFfuT41F0USSUIBdH#--uK%aeT2+bU6^FtI4UyJ#@u=@8MTzEeXdCT}5hkew{k z!bJBrVX37Ok2!R-A!lvM{P5gZ-;|i~tRz(8_Gu?_=?iNSp*!Ujg zYex)@^a{vqm-`W-2A^COcm8Jju1nERou+Eu;6`CBXdwD#*o~TBuJk3neqq?^f3`hY zO~;)x)LqtGtDK&o`Fdf8(QkWx7DR$51z`hK4%4=VwFUysg?T;oTDPvlxiNr0Q?v{ijc&M_ZQlI)iF3OrvOJ>S8plFU z^qqJQR6FA+*Bp6qt~+Um0c$Cch5DwW7#0SKu}12^7XKxxN5yRnuVuAZ=qXP9ahUobKG6u2QJ)H!|FGX!C<2z(n`lN1^wEe zG`GZD6qFuzACD)nSVZ=UeVT)kDGFswb-0&Oz!*Rz5;D~0@Pc;toYSA^Wgv+pe0fh2OU+Axb?W?5 z7%amIyL_u=Q{0pb)e-g=a`=tbav`y+nqLGwkwRk!f!ul%8)=6H&{uJ1)~@2oWUmoL<#N*tydXi<3TL-8Pd7 z2XpGE@#OhkaP=QOm&cYVk+IEipY}BEvmFwKtp&2<|qHy#LzWQ+SG02 zYb$Y-5qmnt8^-Wq2v^q;J-&PwmyBE-HBI*?qm9USedhfhw+ATT+STMLhuQ1taP6*a z|L#bC1FiF>rpv0xmKAxaP|>k*rt<9hzaIWsG8{Y_k2M8=)IcNwOpL|&%-^<(Q4`r8C}%-G|xoeoy(^zzWt!HU&k z!1^8_;_h(Jr-5INtBX&#HA&HlHv^Vw)f(WUvBd@2JM_cErZ^0cDdH6~KfSM)GGT3^ zfl>(xUwprEB!3vh--==cTXk5qB6-^Q3=Yd5{~>)gwr>6tE`dtT{V*uLT0RldxEt$0 z2t~{jU=DKB?EzMd-2b0#7|ny{k*}5}DI)?pVy5RfXdrYWLK5#FF>EpG+;t{9Hlvxt zGpcv=o)uhF#c*U9B?*46+VrJEk)UqC12>6Ze_CPu=hIR3H9!?};Uze9Xa5Ow-#Uz! zw|``fz3zUEr8JWK99ePm;EM8cA;<7aQzT$3oOJAJXC5>T7L<>Pz41<>>7=z@9EdC^ zEFJ7qHCbwR=Om?}%WvLhEO}K^a+9lBQvAD2$F$zvii4|M69Kx%2iLAn{(|g$PuR32yK*`G zY1#Pe*(BdgEiK6U=Pp(79}z!K0rj)w&1Q#iNF&47#kgU;aEo#O&on+frjNy@&MbNZ zu&QSjevMp{_gFKi9JN=jhzQn}D`NqWu`l%>pxx*@mj**cOG4bXa zivmk|F&egJpZLIYz;DU3tE-7#x*H-J{UMcTI5Wg>{=v@ZU} zn3f4Lv=i-M7Ms_WwFQZ#eH|Hu#D#6fVo!b2667gQUiWLfgU0yq%HL;ynRvI{_q2zQ z!t#1Ee|+n$vCZh>Q_PLD*N$3Vc)R1p?ilrDH6^MCt%csF_hXk3MbMaGUWWA%0D65_ z!LIQ_xEbEeEPn@CE^%mE&t#Zy;-5|P6%ay=6K1+YlIn=)$VmBfY^}XcYyEpl%=OtcErV1caNuxPiaAjo#{ zE+q%qM>2$^LTRnmld7(RP2UGK1vZ@#-f|#D}?@cyL*G7Qzrn>lAN`!MZrh~>27Q1a@{enR-gfv5%$wp{WZ3+%s(dg*q z0)0+^@!+D~c(n=iK+}o+wchb-OU?Gzr^sqJ^aOdla?wCH7;PzaC#>x! z(DTZDTRvSUZxdft z*9OX$BM`#6r^ep1o{lf2g~X;w)DRvvX)=tZgY*f{S4tDB@XtJ@4Ymbosm3NcA1Cnj;mT(4eQ2-CbfyIi9pM&qvv;Wg6bcZ{OkQcG11DJ5RX-wCR7v!^SZw34P1G90_Xs3h9~373|a^#&(FoMl_@B$agaJq4AkkG zOY#q6jrHg@8fYN00-|8Bl=5l8Pu6(7x(dA${E$X2J|~XIOww$i0-d?a4Wj-K=4I7D zylL>h@>;^;2=JGuatwL3naT(b{I|1YNvh->+B4=l6^;#6ggCgUXxFmwS&r_pX&|H$ zk1DLR#C|_Qzd4(Cr1Z7iw)Vd1%(+}pe(F3|Hh%y6S`^f%&Vd-JA%HJS(#}V-J^32S zP7v8srX?!sU1`wKc~b$HEQg;(-`2Vx7}o_!S-%jYx%#dcNn0Fyd+mD3w*7xz>1yov zaAZny`Sjc8D~*9VklzF-@0S}Ln?~6e(lFYh?NrzHNh36_!R?S6UCEOK5#;>nU#F-_ z<(Q~>!&X1T#S(y1Gf)9@eB1e$L0_s0|0qlJ`ps|`P-%vTN5h_SsHK7TJDEFHMBf-; z&cmyrSoB{_WQHt_y9{OuR1Tb=)q3sdUCg8jd9&v%#2vMVhzsvMX|K_U74<-N6eSYz zI&d&#%2FfDgq(xf3J1+~{`YZ#30)9%sv@@Pc9OXwVimen5nr6ieq3?$2RJp>^Ha%c ze?nz5YO$rg#0G)ofi4HBy+totp^tOR@fh#8L82#e%gbM8gEiYY`Cd!!YGw!57-nP0 z6B_ncB@b>upx4WX?Opy--VQ+fK~dY3d>?rSZ;%ftlc#H-!}qSV==t{@?Ks>uP-d8N zX}})wL_=I}aAX9JeWZTYYkG&Ie$Kb_*S*NwoLEgTpMBkIvaKMp`1V%&?~{V>0ZvNe z?Ve&s4xi^o!qC?iqtWp_x}uSKCR{gC;O4-z^Wx-_!|d3UWkYn4?Q8qmheZxa93nrS zrkG9af%UPup8)AizGqWSYa2@uTMoN@RVq@*d94Jchw^WAHAJR%){B08kDa&dyFoUZ zfZ8qjSo`R}(wO^M0tGUtfI!ZC1`@PAE)fxt{UKaj+{_4C5zvipHCsWTp{`#;L+txO z8}nEZ)QQvaTWyFU65(C%bzpV4^KAi|hGcJzoL(ZJ&@PTOK^<_{Y}i z>r^`$ovAn5s+;dHb_kWE=S3gSlca@@g+r4EzCRI>Z9_2AFbS2%-pBVai^&qUkJ>-| z&VDWc)EG}$2{C0Qr9gmFmrMP$%50LLTHgoNx|~JG7lKq+sHBQ;b?Y6I-nyxeuie`-KA2x;Xd5Yyp zK)Oc9Ph3oQ`)@ndYk;Ejp12XrH8Y0BmzBc8>}r_{ll=ABQtmIGLp3%>^pt}oTX~qK zmVlfX%MkiPOLUy=T^#+*ac;1qmgkPAM}HZfpC z!<2T3(MBAa{}A7U?fd_{c5cs+r0f!4)%+swGw**ItAX;hLZN)nI54Cq?TtF&P%U}` z=P242Hhv^`kl98_cH#}!<3}Mp3Z3$#O>n4^)J=P(8sZ>G`#1}dK0+sge6_l6V~@`R zITEdr>sb zp+c*LiRtOhxnDe_AuUDo6|4IQyM=%WE90we?I2BcfH!O22hZ_MHdWES5f2j8P(DGG zQ9j0^+IUyJ*JWSQrK*DcjM??g3sf}7zc+#E4;{DVLB+N#AlW<4>sRN&Tnpbvu-u;} zg1>j|CtL}I-&Ilu|o_j5kzNR0OFM=7Zzvq6Y*J zR-|Pug9NVpK|BU{cS{+T6nn>h^7Oi*H#?1pEQMpy zH0_0l#gNePrm9h(U~Vz7$D>l`e*X740?w!<(-|`m(imyHxlXjhAzcAkhuM&NsZFJD zNaOvNI|!7`6V2sSGw}7!st+krh0YOXBz%oYhg@s_8XPTXI(UWk2TJ~qfhAq|7?r6I-tsT}c;eCV7nR9quIe)a$%Iwftl>*YMy?hpvE@!pZYVp@Rst(GSh> zb{Tf)6?zvY8y0QFZXKL3??&5eyOBa&h^&q>DQ7Vzy?>YLvt6EO-4QIsNs`^V^1H0*(+A%U*ABFpgpUKTW?42dt{dm+w17apD$mEj{rI_0P+GK^)$cEaNkD;AR zey(4fzwRv9^k< zhep-`_Vg5ejyx?ebnu7R(k0U1@>@SEo6ode$Abys4GoN2eLF7E;A*R!9P34Na!dyK!i-R zFJ~3qgz^(RI#@O_NwHEp*S7cBxze*~MLpId=AuT0&|UO>_sXqyzq{be#G9im+8*DM@|<0*!b%y(H5%mTdrOT z8p0N$bD{8{BQ4^ca<*y}DMb!3FKkbsnfB0VNk=!Klo+G0Tu`E6b zZQ5qO_H?`ZZ6v_B=;-I{MN)359O8GWAU}Wg1&3Y(Vf*ExG@0uDsjkU=9Y(wbXYh># zE)wMOMk;i4beHsaC%~@V22fyEi3gEHs#gj#CW0SAf^!TU5{UxUl&k|RHVx$oLJ-=RLh)UJ(aQbn5}#eeHj$zeGU1mhz0*eo zx8_th;r!+5)0MqU0eAiZnWw-@@Ha?tza18h@EXD;@x(s@ObK{w(0avBFxsNmB+4GH znJ4X{@&khlrlP=kHT3FbUdqx)G4u;OuXxlg(%M)Z;z4{~fX5Gk}^XhY@?NbXUL@b4cG_BpoDdlO6+Vr0ZAx;0fbR=Js_P zpsg&wV~EatqmqtpFfB1{&N8fPy9G$0;n)f+lmhf=3*Q(tuiDuH{2zAH>ZGdzi(M!` z^J!b43o9_QDJUqkuMhr5p*=hkc3aM|tL-b6X(VR0!MVOX0**&j3R3?`Erh}0IWV~) zT{n2qP3e}5as%wZd9@Ruy!Ql}4^)-f2e%NE?P*8sEi`PTbV7xz_gRsOaJ^kLpEa>< zi3PAS&gJ%sJ0JQ5a`YHktpzYmfVY$}dw_ysov#cHKf|y2JgRN1c%y)d&w~~e=nI1m zGD@}MC$I(!a8cypc_`dCAnlHQc!9k|01$Odkzo?|`89U2u~*538WUi6GaTnc$4Rsi z>+iO;H;iqW1@j-hp7r*S;|R%~>LN-zAT(Y4A>Kr^nUXsk(0chu!ikIvI4)#tKmENr|R>jwcTi)fz-wV)eyOqTUxGef;qAM7D)A;ns6h(q7b^ zx{DYxAz2PsI)08(^YV5&w(pKZIA>~!_@6Mx+fBU1SK8BBelS3}Xcea%s6NgacdSfxTz1@G+ll!PHu2)*fwKk*&<6sCss-llz+W9bLSOoEG_lbC_YY5qgS775 zlJB=>%>N4Q+j;js#9936=lmssJWC8rUD}}J{uu}1G)SwLWTr%~0Kw9~kwU?os&&0+ zWAPe)R|F7Rl`14jUm}cYN202+GIw#m^SNoPq zV)MRR<<+e+piQAE-Ok-#LxO;pV2;SI1)C^Fei*Pj0wj|^0c2lkcbu!uk-+8x<3zf3 z-24k<-dg(bUBYN1jbqTLKXdixX)wF$^e8B{C9!C`>FD)a6LKuBrAovLfP<%tIrHKE zo-3pH|7QX}tNb{2%t-GN8(?X&c@ON(s_Pryxp5Zn{HB6{JIAOK-YM zk(3tcZfT?&>23jOrIGH2Z*BGRzMlJizQ6CUmp>x=JZH_Cbxf>TYtM);-;3vYSotDZ zyRJ1A6&L_9FK})6UvV8rAHal&sBNF@lkbB!fG|Uh_6sk?iv~ZyLc!|HBGyLy`~R{w zCP1fBQ>p>4R;v)SY~7Ah;A9c5Wg$!w@aXox@d)g^=&zwrr|m}MOHsSnbRumqE~@h;Uq0pJWX0Nv#_ zLh;x@iFmV?OYz?p3gi})3RIjqpGN=3m-L+sfs47x*76chAao5#40OndE#a%vo>VGt zZyEmAEwMBVvxijn)8i!0HIGtdP7?ywXE0zPrJkLQjQyVWFaC!B2EFiuN9Q1mF z{h?!{`{l&703R)@8ylOwtxdy@)96dp@`oQ5i4+CKo}HqcQGONn0L=^Peuj_kLUnhy zuhO=SJPTJkJ3QT`E$45eVseQb!M;*qhN*CUg{+k~KD9?_Ds1XBS^dQ2f}hbNPvH|) zY&!bTKwr1YDInV|;ov}cD|A0_!&y5HJB{O@JEkB7gw5j3i@)oiitC})Bckx{YQcpoDv}+>t<4q^$Rm&tb zB2QZbyc`)J?yryuhp8P;Wy+;%UlOWLikC!&Q_(t?1!cKIET7~LZkT9do>e^+9QKhy z5v7D0JXt`d(nG(G>K!F-*y6mu%&cAWk-AlM5##O!Mb3G_ z*TF@of0;S(%@qvBNEsX6$VRk^w#<{MxhsRGXxzfq@E60^r;XRH7oH7|Jn_En2xqkq zT#u9~({Ry!)2fIhQ5Hlq4ZG}~g-ulolgSU>8g;xQ>2;e^7fDLdG>nCg6gen~q&Mc1 zs!F14bxkKd_1tYkpH$U$2Xd!Spgwsg8}s)yMfXMTq7k-kI_jke{U2PJ=!imX$1fZE z$>ixR3AQQRWnawq0TvFfc2%z^&yVm(JDiuD1$f&;Z_*u;-E3udBSEe{jcW0C{nny^ zM{#rG%VV4tRGw1&w@qKhj_!x|lB1g5DIffR7u@+A@;z#(I@nJ zupi59XCSZou4t()vEMX5*y$Q-6MMUz+HRGKAd`DJzP8jU%xA+AK}i&H?FvXC#zS6j zK7_@l*)ZR$Kmu(jTzpYUehdsCgQ{19q9Dy(?sZ&wxaqc3+ZTa8JI&SGr})STMq6!Q zRp1HV$2L5iw*S6q*_7bp7P(kGa1+N4b(Y7|qOR@>4}_fVI(y^d^k70Z2<>Ka;eQX% zBsF-r;%EElrG;=^15@9{L(lo%o2W|XI0rdOMISxw7|pJ7y0Qxo&o2|na0>JH^5#Yl zRzQ;_b=io;e7{#kk>}WU%;dptey=Q3`%1%TeJaL3B<5VNOEap{d12i+y*FsR*EJWC zavFs~O**M@IZ(cGc{~?7O~rw}13KMZoW@cuJ~UqW%%9YVgxwILESk)BD3f(DG9X(j zRpoJ=&sa7hY=*vhYzbzmRMI5pM`f^To_bjt#^`f&&R_fS4QkCcg|KsO@(Uf#5Ms;} zr7d%TlI@!;s$=)?ymPKD2IZ8iY3_`E2BnPz#gT(|R*byDXjeH_3QtZ;nHI}#qN+&K z7>5g8UsNh$c~oCwG#Z_uLJN(~9!_`G@wuaukC*m|cYYL;_N`wV5YrksV6@X3_{ey$ zK6hFwEGQ_3JR?1NxAO3vj75CtrAS8%t7F;Atr;UZYj640y)#cAf?hToWZHHW%GaMue~cyoAhC6&*C#yG_Y zGz-1Dki)h?w$SbHJMzLxQ3GY-pqj9FlkT91(mu``mNr+hVZx3(*dCg5{qCsDN~_>+ zd(>sUpCXi2xd*(qX2II8+9#ma=+4I0=TIsmq=}jG4q&Qp8nw=tjDrew#Am(dby_!p z-lvd6&^?Rz@6_fdoED`AOTtFbsnimKQ{s0|jpBAx+U_Tqd{88a_N?el=66C3$ANc? zhei8Oji!-#eRJ6}Ys{WtO9aI+-3?!`Q;gr_>!EYa9?;R}#AZ6bq4U2i;N(#urRe?z z`I|6%P=;A*DS0hIacL!?vA{B0PAD>2Ec=cn7)HT6UZ^g3>PIuV*T~%LeVWw<4oc-G zU2po?2PF3{vBZ|A%dq|%8d;8vloffrZ<^PnkY_H;znxenlU@9DEI;VVE*a^m%3U^e zAb@A>aPMKW`&2Gt%X!Ch)g3z4rue-Yv!SsDtsPx17IQAumn0Wr*lzH(;b&?AMJGX3 zx;#y_9eFtJ^MlvzUyI~~?7loraQ=d&(MI8hcfKr+-9DX-+tDti$6>8TgZszzg^n>D|;≪ z*J}TC>4>!=>4NY0rwyv?^-A`h1)wzS+93l)ss=egyI4;TdQ<@~hr(rXdq$LJ z5;K7*K`qe#MZ!i4;qHvly1dyCu`$r72upi^ zDY?YuQdf95c^}s4U>Jgd%}u<3?y>tSdrdd%3^ z3wv@SOi0Mo=toAoW{ga^)CHXfBkKNcslbRetA{az2@NeUC|)l909Xyb!FSTQ0en#V z4ZU1p;h>-t*eq5TDk!({kJ;S$Wj0qOwLI=sj2sV@iVKROZN8HZ)jUcaG8QxwcH15% zYS{4^u>HcS#lD^ z>3R3u{SCvtBh9Uh{P;Q~F$bz2_YLpB67W`brDFyDZ1;jF6#;GI^9N?dIPlA`qRc&o?Nzd~5pv+qIsj|Ia( zL6{`a3H@ZBL-YivY?kOr1SL!KG_?!oqaPDClqRV9PbW?J&CXB4K6il+LM+)VmV`u_FY1 z{eTly`E5xaNFXy;-o`(Z%C*=wMeZ9(7x~@^X*wWva$9Eo1l&7#4`V!<7#(5(iqaxR zlbJJYILKt}x(<)l^*EhMYD^Gd*qjm(uH!mwS;XQKZrqD30-kxG0QB4qASDh?adyE+ zB|``fDHOFP0zhJUG1ud{9}2EgMXNl7?d=mco5NU3^B(0Go3SfTPG*PHRNPzb)Cy=%+|u*u7F(2svmPj37;bLm8928VF1r zx#&K4nEmg=tG(5ameaq2(BKa08;AcvyV=9;x;yOKR<7w3%v^&kBD-|baA(6MkG4^7bp!6z}5oZ%awt^z_z z1pTqLstKVlhzeObm>@Q^|GY2|Q(rH{u0A$ki8m6seiy1#SXErZ#?56ZbRJnaJ2_dv zP}gm2(ry=Jzfi$={;H;H;3(NJz+A#3D)D17tTHzFK~#7BxyLWO7yrR~)Sel=Rkb{g?7GYCNVA@Id~|mMUQ#pmBvig{>ejFW6!R18U0(zbpS*Jag~YS= z9*isb5rk1g@(%b%&id7*yARmC3WbFYtssly{{Sv|aDK61rl$Vch<2mQMAp;tM1n`b z;hUJI@Ps<9(x%1S*Ato(4bG`iyuAB(H~8F-a1}#u-V*x<7N2_ylxcxe=4QYVQTU5C z6ZgGuU+YTU%qj~rhtSqd^*4y973EkbaqOmLPo(I3y24A~GU*%jmq@48c87%f5!an< zdui5W&LegJOSe%_@%{m58}6w{Y#Fdqa$yiVUU+IZmxpmeeFRXcl zWaN(4s5Y7Uh+eu|b~FyH@^ExXcbVZjJaB0@BHLyzW7E~sRy*!Avgt;%#9#gatT`)R zj2;nNf94c85m0oKs2mxGUGKS87ddG`F#>!QkHTJ+=X~e z&_Xu~@Mce75x&c_Z~J6<<;%jIn?54HM|iKL)e=i`V-<8J|D#`=;vxC>$H=N+v7g)f zv$`~-gAHomsVJF^ZE~uwZag)FW)H@l@(S$Rez(5;R*VV>dBpO&wImA*sESJdj|F0- zZ8+O+fk;z<2H+$BTXtX_0qxnWlZ$N^uWY zKj%2(k;rne?KS`Ob>J~28K||gJpqf2oVO?RYAL+d) zoDxJ+uzy2dD?Bg|6eE-VW4%Um{0FcSfP>Oky%kUR8o7YCIQcGAkzG$IY-8lhM2=$A zl}4p`iCKZy?3A#Tif3^(ZO_un16BDt+7_!BubdPt-9_Y192q>(y8``G&rp9`h{Db` zP&YP(_K$_?#@PinXS~Ak(eV}oO21@43Xux*;+}e&WQPNa$<-d18jIza#N^$uN{4j^ zWai6-_k}3*Ui~EhgY1naP-Sfp=MOT<-6BrE4=s=i*XmX~UfaMxHo)p^BlBP_ZKUBC zI?e^}9`e{f&(~e3=FHaJcSoPtWHX05geac-al?!G;fL zu<|h09RO+VF}wOvU<8*O_qyrxGD?+o*(XMq_LkRFHt%X`p5{(TAP1*d{Xx}TR6-oi zzY)VjdE`wLiSkWtJefx8D~&T_wqDV}R=~OedZdwM(Ylc3=2#-!;X%PtpMlaoP%m}k zvGSfIt|idz=p3a+V&90tibcCVlazD4J5VOMljdjG5=O%Mz+HZJ;pbHUU;xSM-)r+z zx%K#@YviZj6bSl3AlB|P400xY5sxQKvV_!w<@?Nx&7(FpDUB;ODkrAak7|aMA`G)9 zCdw}#D#$))$5LweQti5r*EIh}-6*k{{;ed(G(y53v3R}U8i(x~g&Te?9t34^_4RO+ zq44$h>Fu9YgyP{20rt~LJom>W!&$AimM$cyc;1OnuNti-d;aW$&d~woyNinQFEQmt zy1Gtzb>{3=Lbm zAS=tu_XrQ#p$)s3iT1izd(nq}$8(;^dN)8LA*wuJ6VK6>hDS9^=$2}LSJ}+Y9;bx! zd2+=En-4c_H7XYX!K^16mI4#l-?L`67BMtAvfUE@l>b+-`O6`LvEI)E{y9(gLp?7H zZX*kVKAQJ)&inkfLc8cz1V77|1iLO}Yr(ik~UIb61Pc6K!9&c;+5 z&t7_-xgTtVExwmR?xRAUWnn4A74;K0SPWQ`?6VIg>DVh}3Sa7aWLhVn5yuueP-AFV z!bJM?w1$3FCwDBN+h`)+T#Hbr&U&1QEw!wDXgJlC_OHi6gh;ggRG_#kzb^;Z!>|s; zq+c1ow@$^?c*KjQLgpn)Pc*#i$~7yAOz-b+Y#wqJY1X*(I7`-g)tJ0AHhWQDT%(7c z%~b+F6|0Li1ds%K_D1|dXR{ApBK{!2tjflDs@_|6gKvNQ{f3~)7V`6lI z@*Uu@bRDqqzKEa31)3olq?HS1Yh=X67!y!D-=3?OW|K9tiDYO5H>e9KDE=#m^yfeY z?VmuT_9Zx)NXPZOo+z2HByC$tmLt5p6%E!U6BvdtZo&W{4C4%DdZqP+QiI_E$1lq1 zJ=wcBEa_*m0(S3~oS%(1DuBpzcu#&g-N=v9wpt?jV)3qU*Aj>1`Z$ZT2Qqk?8^FO*zE6e|fy%%VG#@ zl{`KxNS_5`8~4|NIN&&Y5!EF}WB>Z2)-6GexNzq4_{jUfSn&yNIPA7-Uq(YCzPx-G zS>(QHHg|+5SPpK)5-uQ}yg#Q;Cqfn2z(MO#tp&;%>oc`r{mnLzjb7J0q|YoW>`X2nMTMg zJ$uq&QF>|u4|_Ju#F`sF%FR~)fOP2PJnrpTIS9V$5UsIu$5_^!LAPra`RU|l({hM9 z6jsS|R-bVV%N(%)^QrAxVoYHBxE>dh6ap%d^1K7(wA;i?@k@Zo{AuwWq=bM7T3<2& z3te8r1ecWerL~O3dzc4%XT4^(N0HTa--+YKGbYK} zMI8hAnpph|BDYmc5v>pTJ(o4?3r))khLY-H4h2J^Su|z!m+!*6Y{b|cQ~`olb8iHu z#3$cw?#GR|J*6v@wXr;sG3m@Ag^{!wD7%OUUG}oU|JHH$cj@<4rgP_SliZcemqxe- zD^Xf`Z5JQEWZmyma4!*}A&=Ew=e~Tuj(kd?cvW*xICn8( z7uXYa=wg`E5a9YH8|bRL$q1{|lB)Xi>x@1vyNq{mnYg+_Joj~>b=AT>h8Yy*9d6cw z-4b;Q;^NcvCo_vPD-&M#im_guPK zT(j_}@=aQC7g|eX<(fbqgr$O3WsWCqGxJFeCN2{;(_6fEPmGb78%;fHyX>Fw^Y@{> zhZz}aUv7<>lvoSW)JiU|04EQA21O%Xk2gs__e65F(;<_vo>vYyIG4_5pN9&^?>(+P zwb$>9aHHB&^rgJndFk5o^(F+}^d61z8f{`kqo>>ifJy{WWM05EgS_=2F0Cpirt2l# zg_%S1aWr@JSj_f|&BcjA&9Q`uiF~wJ`F!RgIK#klF2mH2Y=I~F?}l1$uxh{-aik4k z*#H-{`nWQ%YVl~A(I6z>OT`9ik!Db>36(VF#zUoBA#lJgBrr}OfgqU!9{9=NrSZNk z;m->$8QfRtOVlQF(z$WUY`aD*RWHq=bTT%!jkqivURb*mc&c)VMF&e$@FU7|Lm+mo zPR>mspcqztYYYV9JN89-kfi-A)vN)&DLvSq3_57Y7IEQm`}Fw=^&9-mjAy_p+n>q1 z6X?-z-B1=h#r6jLW*2p|w7lVaLc;6>NCxw+=T;e8Pa6Ng6vC2CDYUm^zN)e}rBWU#e(46Mi)yQjj4 zeB1r@z6g9rJ^OU$50D;;ifM2V6#x58@2s;Q6_lc?;B3MW0%rF}>Pc`}eRA3OnGYI64FHmW& z!(g)#nJhScr#+2+ft5p?(#~{QvuSOY?9@3(p3(na9?=|&?e-b-?&N!vR1?n^)Q~6{ zR-c_=*F1g2sl2PX_LF&K?J#Mxu8{*+YmZsn2_-Bom#t08RtsG$U0doAmf0#ZBMFh> z+e}_#KFp;{A7|n~x$kAq`qzzd4?F5hyGXO(qVaVRJpBI}()nU>4dl(s8qX}DeFJ+8 z?I^}iF|IE*#FC+uu}tw{+$>%pc?263=_h_vh69`Cys6oE=P_3f4PTFGZ2yY#DgHFtl+ZZn((Y|Ot4B1w)5q?3U61R^W1tHr~M6y zLVeuvD^G*dLLo(i?u&0PNtmW0gZcCflXy~H3>A6F66;H*yK3!3%H$?z{X@_gIh&=C zgX#Zh0}75E6c~%^Zi{?QW@7mVc<#m3BR28$Wo7Y9z2gO;gep)wH9JmpP}W_1Iz5vZ z?_5G?jQrTRnpa6sh%3CQPfxSR=ewjh9g21D!zxAa zE5G&5dPY#25f|@Uh>0OHuYhzy#ropXbX!{mV=XVP7i=bOLP1P1an@lV%2w`f#gYKZ z*(Wfn$&H37KT8P3!0$HB*oZOxgMdG1_wC2Uo3q#)!{c6UefQc-VZx#t{`P?j@{B+Z zN|Y^8G(%;+mxDr7NWjQqnG}|G54=IH$)-DruSui5MfGlFkDU zpy3ud?F{0{%}>@FOyj6u1soDf;+NCFo`q>h+x}-mhPaJS!A7Z62r&IsQYp(1HiDF+ zq;GE^VT-Om={D|s(8Y5?OGyN}vu?PtrX+6Oh_)VC(+hn8T&0GJXuRc9T$i}-GeV&r z7ZlZ(A4exewyn7&QvawYF?41oj24u>E#3z1P>Z;uI zUct6R9#fl3+CI*F+Br=USb7i8!zl1(-?EW!?XEWyd2)Q$1{XmF3JsBqH~fd zOfc&;oEj-9ye%{X?V|>&1doked-j%_cxLXs(!zXh{M&ztwaYs~GeDGK#q+^8A$%h7 zG8<^B3X7@D>&#n)9&IJBJHhs$7gs($u}ZV2_|kpQe7cJ{9x41O(DhC$6Aw~ijP+;d za~LsS$G2E-UU{vLT;N&4G22OEpbLOE z8I;o2dXVP%osWb)k2brE@M2}wC87T(wFLp6(fyiZZ;?0vp6H9KUJ*koIUxF@Rxpx3-1%C8ODF(YW#f z%s_R|amskD6*8DE%SHG~!i8zwv@kK97fP=Avpu7u99>-{&&^6YRfnK*7UA36dpg_Xl02S}%twoV(zlUkkTMGZ|>E;82Qh*pX( z%vBYuhG?T`8H81#YDm!*>Q98i4E^P9xsJiFw#vaFltEecr&!A)9h2Jxv7<<-KTM6U zh@=}}OPbFMUBb6z!{^j^$FZD`cg{P-RtOF;RO&A>ooz{#|D{+GQiC?}3D2<2;0f|! z@mV{gtSs^)2wfo4!i*myl3Tt>ZTbDoH~B&b1THC$;{4U3jQcklPuFcO=X*U&YC})2 z`md!%wSo?4(#SbODv*BaiT{p745#fJ#SM`Qj{BKuS6?d=lzq657D|`Bjp%QORp{Fn zlP$oh6BV_C8rqP2j#jM0w9yl*^JYFb9kU*bZ=AI+wr^D8d^PfkY?j|?EXKc#F%7LT z4*-exyF9&py03?^Oj_JP z2O~s8=8XUrm6rmj`7Xj!MZ&F^G`9Orw;<#wFacBE_mbdn?H)f_RJ3s{f$+EK05^v$ z6Q3U-6_q8Yp$qFQ0_RzP2IQAbS`{q0c;whR+?i$p!X!Q>4Gd{yOe$n8Os=owu}tTl z!}_nQKeZK@5iu~BE0w|~LYT%eGP$+&$24-s=5-VrYrifMgR=VwdcT~^2EW-06+fY( zzV8rJbk&xE85gZhYcchb;UfG?L$#i4dE|n|?)xuj&1#=gMu?eJcIJsUC;O89)k3h1 zQf=`@<@=#1)044@fA-1Rydl`0#@Hl1GZy3{&9(5%OWkQ!$^Oa#4uMpWnD&EQ$?o;n z67-ri!K?I5aK>=NjY!QQvJkG?r}n_*c@B#i_r=1ruV4D7Ec^~%P=QB+K&-d~Ov$DQ zK#M&akfn>P^YIxC9vTkvMVJEM7+;SgvKQi775P4cdtzOz+0+#|<-Q<^1*S}8I9&|v zEi!W%{siN5IK5Oymz`w9J=T|I)?B?B5(PMRVngK)5t~*eWWQyOFwXwKxid>vEMa+o zNEp_J63>5TCRUNpYT*(h7nOOcSEZu9y-E4suP{jV06vbILG)e_(ob^HKdW<$WYiay z_)$|=EKWTwwURMeMMHvF^Sj*XZ{dI*FJU;MfgqbF)tZ@CY1ai})<>~@xFZ&ZCFXv^ zM+0DTDqQ^TaSV)=Owipua8lqN0CI_0@nf=6jAiCZ5mpS*zQ02u1YE{EkT3tHBtg1j zKIC1O$0oN%9Iq)^ybwt9C%RQRzo;~?4DTvY+RO)$>3XBL64Q(TT3+I^vhm$FAcGE$ zc|g8dSB*9S6#7Si2E^Va`8Z{033IXar|qX^4sse(EDpF;<(lIpuPs21FH|T#L`p?; zstIvwqCLC;PM6B|CUX20R_Tj)!VU)(mTqyt!KIxKx**?S<30QzIe(yC_5Lzp3HJ6w zvJS|bP|QqLE#0VUhW&@BUy^>e7zBHUSaMM#^n`$vp^!yXz7k2_e-X&?C~>GRiJ}Ej zz7)TW#9(;p!QCQO&z)7a1+?G1dv_^|g86`xZ*aO95>3>fP%DNUT-XizplEFO&VE$a zxU@P42Q2crztk42NO3IcWHc8@{!6)-fc>fMkF%0qkys6IbQnJMI|2lh#iFo9&p(KR z2QpTq2Tg7oQT|6*ayVrJSecZ<&fQKlnP59?0yf4lbdbkinZ^3gQ{1%1DUJVzLHZw; z^cxia|NkR^dg-XmIDzvGInwwzs3$laj4qsI_l%3t0nSAOz5`UN-(jAND+H()IPK|^ z?W_To#be;mFMjW*`f-NQ;)D72;s^g3n?TSD?6?x@>sjPIMwjB~&im~A%dV_AV0YFf z=CXq2qQK#TiAy)dZFXOquY4|X-~O}%gg{pF)1(IxXf02ULi@C`svlto znx%sm9Q3~dbW@5>-5)%HPvMl+&4UQ!noijGqaes#X%;)qGC7)7ANnjlI6As3S6}H~ zJS-Ymmf58sl{NR5pBlYSG{%i0z_tm1Ls^X_aD7g=d6ZeUG%pMG1JEOk%cwauL1vaM zB z7NAXIviZF3%u}Vs4Z0unhTQi@N`%4p=YK}Q&TDSfeo!AVn6Xvjv0xZ*_)&IyrX;Wb z`EQH(Ytnk4O`a|@NM=^w!b3FzDI0$$U_WbrtW1eg9_%Yw07?xP;?VfPWz`7qfjFKh|7Qm+kd0mV z?bZQbDMq*Xy~Yerz(!=Trhji5r_APk?BV@{GIbp>$F5lmnpJR-0I|gdKh&h(QC;+1 ztPM*x3=8BR&B(*A-p3v>uv~((x3DF!(=7EytpRD_-%pElz9*f#FFhD1%wJvjQy!VQ zXbYt?+>^!&-XRS%cbAg*&vQng6DQiK?M-=i+m7NmI^Z;piabIJh}mEM16=HqDpWq* ztLdPC6aeaP7~rs@`)EmW)6fazvwTRH;+JY%OBnXv)ej7JOj!JtIjX!NvOCD?%EK2l z#5l=`5dcy7`iZ;bw7PP6*dt=e0s23lEjTp=-O{qr0q8W=k!SW)h1aDE{|9@7J#}A+0Rx6PV~QxS_3`4NT7h6Z~eWZ;Hvr%SQE>3h|qO0IQgZ zo$WK2jku+Sl_eYox1-`=6}L3Ev{ACsGk{TXv2lP$U$9D|hcw14}~~ z>l2uXk+B^W+haB;s~ik&WM@pp#q*e(gH_31-_F?z#`@Gk&j`kHh*MI$NPv~arqnWs+`6O2tLC71U)xaB~2r<$VzsLFYixe>)qQm+B`}w~r z0e=pYi4K#A6%bXwIlGhfj?g_WHfBEp@Zd&*!Dcp;t^WSLF!1(Y{66FA&!mNN5b5`Z zf_2(a?`=(!r!-Wq7dGSliPp~tD)hIWanQxQvClJN}uQGhbkB@RsbBHVi zFN$clr`eM#qUd*TBglx}@rfzhpsl|Bb;S>mIU%bk(3A~N4j9D;3=Qb*88f#%_UVBq zd$u+4bjt=Qjn!iQu+FvXq0VCj!%#{zIx)jo#X?k$2#!uYx|Xno?Pq2bH*=>;Dhc)b z6agzcj6tmx-}9;Q*_Xb%^wuwCBz${WmD!_w=hOrc5b`Owx0HO~-Bj!B|@`!xYH85-z~mVdH-VxFMHcncW9Lp#COQ zk1DEq1zyPhsVLE|dHw^Bp>NT^L=WA4_*#pC+OG#xiWd$NzVX;R&0xO}haMgZPK7Vv zfX_?ukvzx{i;-fi0mUOm=cu>ja(=3Y_E7aHR{iYLtq2051&tq3KUU&)7Z42JmaMUs z%b;)&Bg2cPBa|+r8AMS}*P~>iX?@@+o17*|0UkPeAut&HP3EaD>63zQ(yXkh@J^Yb zceFJ9nU-rD4<6{<`ZX=28UImT!>YHNPl`}=W5h-=a|ol(k4OFYNC8_)WuioYQUgAh zefmmHt2}xK^|K&bs~qg;L2<*RmN~*eurq?#g~kOkzE$&9`_Yf@d|*7s%IC8dj2_6S z38r-7l`q{2p_1%-F{BeVhb_uY+pDuN&qZGHX+i5MN>E1f#`ipSf=6DEu#9CXwEznz z{%7z)oo`!>49-lS4I~?cRH|S_m3p*H5VxnuH8;Ytj5X%ate@-Z;ueN2fB)J3@=A}c zgitDlGSgB$Llgqpyfp*qOfep6ev%kqJdB`83I)@Kd9M zadOI~-hYAGy*elVBbmO*odpm2?I^Uf)!SgSLCiNBNo)hc&N$6z$n)PNPT!YycFK?~ zI((bDTvFJ@%prKa%Z!KrviK&X?4BKxQ0Ql0SEjZH*BQOfQCqeS3)zLO6=lhm0>5uZ ztYE2%XK}Z(xa4W6<7Bz{-S2CuCY)mz9lDy{%QvBc?3fN>p71QE>0Z;PdlfKx?5-r9 z&->?+@-KPCpN*|QcP~2p9)*_0chnSO*NOs3!Ck%WMkdSl$uk1wC9Vn`=5rb`ZMguu zma=)v@_}Qe=$3TNc4Car@TYDN$iuhrFCD2cK6|61d9pV@)LYd1#6M-GF?8VhC0ffj z9=>v72p(Ag&zt7pOF|(jX!LobUyQ0`@^01Kp!7>xvwOr{aQ<48Ig=Df#TYhBX&!|U z{;HO&FVc;v=7w%~V+`E4x(D4QYa|srBFcTeeDH<+bL`~NSBxH_`#0b0`8uJ1%*D=t#_l7`6h=qL2amv`%pv*EnC2|XuU@%%1L9J@`vn@f z$@KXRyZRvtt*2aUe;po}wB%U2q;bE=(qNfdG2?Xn9#)oQylqbePVzG@Z?!ue%;#ee zp#_sE7sHj<-slE}16z43!2=fcJMG}zm$w^(KG<6?4Q7zKGf#14`_28u#8q(;lN?T|FO z3`^a5izMi;C3&JVv92^O`bq>Z%1mky3=hbK76n2nDV_KVz=_*6}Uec zr&jH5PSvjZT_|zW6fUVT+iE+}T?R0zD32C?C80!^PA+`VfJ@Sy1Ls{Glj-TGj zkV>ZHhBS#$v)k4Z0RJ*>$lj@piB|Jmjz%cgMlOJ?jL>c&&<}6sO;M*yS*OackEGma zmehhet-i#^eI`t>z- z-?LR;6`-2zL3_W(R>G#tAv3r48E2=E(wwa93H$WPm_ONRJe5>K6bdnY2gjy7c_?>t z{9DNFyiqy_)4HE`UwiZ$jBTfq#vvYPv6FH8ZdN?$)RR_vMR)w+spkR_LGTb}{by+? zMRWwE=EgJ9 zETwrQ-8a>0y*;{u#22?`KD9e>HEuuB$$af%hm^uCm)(leaC6@@`WmU`dDNj*y7^{6 z#bxjEkgw1`9}8j2NXoLsTGEW5RuV{S250LP^aeJY5c?8b0O58tA(%oEg~~jhLw><_ zuYFt*sO+on*#cSV_Ow6hG@>H;j8XNFJ<~{ctRE-hQl5wm221A~B`KKuu3yM5>!ca* zC#+&+TOUZQ)G3llLBGG#@Od&16%+4cK+4%AU_w07fjpU%hHM<9` z8DI=%iN=?^H=Gz(rOaAlhcPXU@>hW6b7QZ`8Yze=|LJPcmi71Z>c9jVx`SUF$dBYy zn0v9jSIOVfxKO2u9$Dy*BKX-%ZVAKpvTIm>&>LIz!i9o+c z3~?r!PNAg*2Y;)0048{A#@LdFb#3(H7id2i`!O)C4cO~Z?rg`j!J2rKkjrmTKR#C$ zu0;S{DD$;t_2$X&R2YW>PfQsEEcRGM`Nt%=s#P_4QD{n}mZdb#kAz@vn-o%wAyNe; zf7!E7+lVPK0kTI0nNMy_R?rJUG(J1hwDDHd;?4}dpS98<@8~{z$%>e`M%Kt-dO3c} z$Aupt7WIKS-8GY@O(!Ms6;4W$p*UVMn~3*wDl;s#7PeaZ6oe2^02A3Uv`MFz zHRw)t)B`!{hyg(RrTghHKIZ)HgVrxrexg(RA$F1u141r$&Gr<<3w0>cjX1ZNiCSDo zMAbRF_zT%_d!kxVL};b*Ny)cP9i1--DWsrfASU@L)nljemBXB&TeXwPH@2bm83#Up zrbf3?q=B#eB6;ZUtAG`s-5Z1cC119W?=kGyR+|#DNT&Vaz<`gO=;eEopXl9;w!BLl zHR1<9AGGqG?En1PwHw!9G`o9S3KdMichiBUe0XqE`TP^Zrd`EVq0KkafH-@EJ>bh4 zX)bgMxX;NFE-OK1plDY4M94vmM_nb{QQ+`%dx8JmH&RSE%4W#lhH$$_H}Apt?$Z@3 z`s#UOC}$fy!#f%a76OY%2FN&zs+LLi-VbVxi0xo=?qb`ocRn^RYe^#=WY1rGpRqSt zr)r-pGD~ zoH6o<7FZmeJCyL5_v+Y%Abf24FK^j6p1Ql^&U^~tN7r?03d?)w3frF6gr234&QO)0 z_f&n-2>%)^K_FHL@8ng^pj@}bYK+RVUx+#JsQs2Tj@^P$Y9D!JUq|HMld(&!p~^); zruY_K7KKLbL=lT=7xW#+ZTpiTI-rk-);?;DviRw7R%)=2YP$bUDPjn2aTi#(%1`ei z(p|4Mftj#Mt9bfEFI$)?D5oLE5?ALr_LRSN1a97a0iMmUa1TaERh zfV6^1qDIRVt*Ddt!bT^B^mEGMs;}yGl$!bn4QdNXtSnX9p8-Hf`Gdhx&01=q^`=v% zeKmSISBaI0DWWHDsx1UQ43R%jKR=W{V}-^b<+gYpJmgt${l_nOY*1gt-* zb304L%Jwy1#`5Y6-I#Gwd*~uK%h8-IyNFxsl%&RzkrWt`eJ_=i*{3=TyVA!@4%(}_ z>g(ohUwF4r6j~!{G82ZESTgJfH+=S*Hb2K)dbinP_S`Tnlp-*s@uIe=^f3|c{20~O zCz*EXvE7>c4W|{~4N^(90S7Ctwn6LdU3dntto3|2J`86u%i+*o>ft;->i~Omw3HZa zkO;?K2y|~|Fqr-o3tekLld|m2e2pIWi-(i@$LzxQj)#Kb*yETJk6Ci?q=l0yH5JwX zq0uLF+EnR-^9fI!$dG6!7-mTt`uUTF^v;3(q0?i@Z(+`5pldy3`%3L(`Ke`OSBEE; zKLO=AkLJN(a3S`1u%Y%8K=h7*b?q$=$ExwwSwA0x zpH_K@)48gs$~m=mUPP0{;(`~=R@nmRzZvpjsi^@{??D?kzQ)t5uo{oTw9B)&%9xC z8#@-tMT)V~&qOF?mrg37qIXZHQ7A)U+P-B3XF&+vcqCXi@LI^ZD|(bIF~p}cI=$+S z7H%e4(`Vax@|DNjGLvG3rZecF41?@qDWvjWwAB1Wpwn=D9DPi!{fY`k+L|jXp-zQV zQt}@U^d;iyOYB-|&%(?Th?PfzJqh*Capwlv6A2H4B5K@h-m7F4Mn5hI(AFEueeLEx zQiZ~|?c|lJRz@cj_NKZRtE6Jcs;+6RgaOF6q+>Jh!+Upko?ojJthphf0cFAwDmE*a zi3#*NlMM#Wl1LI-UB!*F`lTsg4|m0Nx(;>LeZeXy>V@Nb)dY!;^j-WEMj5nTt5SH6 ziN>0ySoKJ+c)O%)kcTlxzA-3d*wbn#fUXRDxcWz4tfa{b4Ds1AQr!9x zo-dYZyvgv2W{1B%4KBG}nW$}+y^{_^Kx?&)<+2tc8Lkd=C~J+s6nNnaR|9A*LP{^jee5!7cM}sostHh9yzUn zHp9JRpjWW+)%IMcyZ!`SqGf2@8ggr=heXsNanDNzju)cE0~XNTsgrU&a8{)j5JFJC zb6$*r``K0OB2sgssU-g-_Z|RR?oTN-8LP2;(uhqAH}OFDLDpS*SWD@twF|7*XurBj zMz-h4I%`BQTmtVbi0OYB_fBPI$IYPNe5wHDvr4`+^fe#%+f^7lK}+_m+9%SyrWmXj zl*`S0F#(6-{NJ+X@2QGi(2ey66s@9jWLd_wI6r=;+v{51qb4l{_jQ`pV_BF zliugR=T0cMjI^b?Q>CFQo9m?e^S6@RZ0rrV)M`GT8}U7HkHJ`fmDLk@)a0_XCE}k< z6?2KlBc;Ub;OQ72NUkdrLXQNrLwOvt2wTt6cszJ^@({BxbmU#mTp`lZU^;1in{369 zvYvXGW|qI)%+AXe7@zsX@x=#(5PEY%W>Gk@p87w+BP``_(s;j?LGM}cqwZnsN85oT zm1d^(vcQ*>siZUC(PqLnJF3@!(dn+l>zgZTM2)Y>Ba5>$pvtNdel6IpI9{J&w@^s3 zWjSOy8hugni~4L3>~v|wyXs+*h1UEMNtAWKsqdJT3iJ% zU1vb>Qv%v}UY~*juPu2_{Yn@J-Cep)8o*BhPH^ z`SMUinut%#_yeuTwrkN1F%y9rJ`_6_fW~J1OcPjg(t#!w_L}>S?z_6w!INHKMvqxE zoYnv_qynSE`vF_EwF@&_PF(BIZ=b$(^U9W2My#dB!MhC#9JG@R^kQ$G-cJ0iJ*9hv zvWNnFqy2uxH+Y-FA=&i~DVt`wpJi)Nl6xNZoH<9j((-wE-kZ#F1np-~RBK5rnL_HW zQwo#BADoe1gGnV<1lNxdR288AA6s7?5LMUpD+Y)-A|Mh&h_pya954tGM5Vit?n4b7 zilo4RNT-B!Hw>jT2r@(0fPl!*9g_E;&-*^#{qFr6&f0sgz1DC2)>?b-agWVHWKX$0z&Ah^B3@mqhPnGzMM+?zh340VM>h?tdQ=GaGR=L@!{Zf>6ulr!k72i_ED~a6 zg2T$ajl8n??RL7^Dm#vyoaEU48%|$!q=U2vXIk9ROl4u^K1zxb?Buez03`V3$ll8+ zjaOduo5Fd`p@PJDYW0h`-?`ub$2H6DqIhIUj8+o$2rNWN(HzeU>4ZntCg{!CsMybf zlS)r4zMW@#9R(-XJr1FmwA)xaBOyPxIK@nJX=t%zX@gg7=LfFLDG%) zjyNfc&uT%~t}xoit2AjV)PvODbrnUJbXnJIa1>2><$$63r>>f%f z&(sr|eR7&~I2+*UdIx^dj$h1CqaijTj>1WO)WLozz&9E$M10X_0e5wXKPmxj4#qaF<_C(F`0|WuxX0#9bU|m`O-1wlkZH%Aq}vdN5b+et^GP9Fb9zm;raE z>OPFcG@+(e$XgUpo0qG|G;?lzo<9nZAPEdu)#SyB9Eo(F<^drr9 zbS64w+9#lJ@OAo6EeS_wg>Cft`%iqzssJ0-72o9O>BZW4hMOb^2@V`S;^zLM-6M>v z=-+V@#&S^Ni|u4Jax*`ZA5F_%#-gvG@N|ufMgTN&77PQ;O>>s;GvV^D2@QTF^Z8v3 zeuzG=Y@uKL(sD%Or0k&(#$OJ(4-2k6L@4g*qaiA&7Hh?4y3~F`^Q<;k)ucmu;wugnQ#H&y6`W~zv5}(2D|OQE2FFR zoEeYtFfen1$U;G=9s!jvddtqI7b8=vKhUwNyTcy_4lcMmhZV!J?QfY`0;wj_)97vU zAdpEMpf-KEC?$Jt!R#qBC199BuryT1E8)9>`sRKwOA9K%u&w>V1vm>vfrG7rCl}~? z%V$dYxKAU@Bd+{W9Ie!0`?D6We^h5Cy(ndK{kicEN(}km?QuPtw%kA}u27L-rJc7U za0A0T=d%-0pNoq^W*BsI5Tt)5hIYGGC)~F6r5pyS0%Z4DnY~;LxKZTMvO}R5mSwR* zR+#}wqb6L~HKqgx+IX&W)Q()mz7^!XWtjCl28WNWcY`L#PmIEB*`+wYzf$^*(=;?x z0)5YP-0KoH75Y885B^d??IV zw?)HDMc@8Acx{Z~)Hcoc8E@F!&5F>%n~ur*5&-TO_iIRJbE$C78`H4f26F~ghRejzYUN<7S9r^;#7F1*e zihMHQh;0g<&xj0?8x%8?e{32NFyQPrYLYTmcVb9?+$*#r+(TWn@cKA_yKHy~D*a%O z$&oSrNU4o(V)@f^CqM)^7XRcSUGWnlc=G^~KY*W77_;r-Nj3ugwA|LcKVKXN^dn6Z zie7z~5(6sI`I736!lPzy#$TO7kC>LBwu@)q6z%YY-aNB9xN#~QbaoOFysntOwd!*1 zY@zz>RCnYz^y*yk;g$=6#ztZ<`HZ!~=?kfG<({o5?-$7aq}w5Xo+xU!OL(f`w$OTV zCJr?6mlcqDp03eFufHMoKb~P^&2r)KP`CPIQn|M-%F`TJE~He4xr)PAxrpuTN7CO6 zCODQJ!AKAxBrH}%q5H)cruqN#8gx<^MNt@13+DpvGFCTLq6;D3G9KtyCn6C2lH(kFRi&fr9sx$J>=&XMo? zg@xmB>l8Iw1mnr0bhzw*A@<6+qL>h za9iEG2W}55As`nA60)zLHkH-lH|Q}imwMuR*5xU@7#MBbT@Tyf`SAcF0&Y|uoRQaN zphGiA5vy%I`AK`Gy zD&hd*P9){5IgKGfv4;hNB8i2%lSIpL5gBZ6&WXLZ4gSil&xPE!hOtdW=F@Mfzp~IU zPK^MAB-w#Us`f<%zSiX#>j+(oI+|y+7qRH(sZ9y11fZpb-%WmjFeLin`s)id$Pq$WO|ZB`{goK$fM6sct2f`hX^Ia5~lUM`*3p=ga774NmC zSj(81{1Ol)+>-yKTsK1)s1X{R?K5P(o5Z33Q0 zxWnnnina`RuP-?G)y`(_gHveHEX{lWW(MtGRxVj+Q;QP0aeyO01wKo}|#Y~H`*iQ#mAn2fkaX}Zg zc_fd9xf~$2z9+9kcehk5!t=krF0YrrZdjTG3&`Kq);`yc;%MVu1eeAbMNVRit>T-m z0i-rNmU6gDreNJ=M5ErmX~81|(3#cLkV`V$QwBbuc9 z^Ht%&k7<4i7FrD>_b`Nf)z@BX=ZCA|cF1kn+N9Q}I|e8Wwa5QZnyJB#$5NcXtTo>A zJ(^E9c3~rRh?kXtpR{b{jX)M+m3G%-aUA}!kVPUCtlv;yO98Ek5@OQ?kCaX6g>u|W z`?P7_6PKvvs)@Sq!3(1+scqWe-A|@<>oMC(N)u%x>5w@eUqLa%lJ2`Thzk))aHElt zkr85^8hX1o(8z~L{xzfVX3nZWv)UD`D;4b^^8L+|$;eoZr!8Ji-gW@1hk!}({Z=7O zs|ObN#CzXv@u*0->9)Z+=2L9Br#705G?$@%V%={mgv9C#Lag*&o+ox=IfeAeilW<) zhZwN*y6Ztr=;P7`WjY)h$vtKGCYe~z>~_%j%!yn=K?*?(}U zWr7|A-O8&*a@hWUBPs!SmQE(mwiG%!s@O;Zjjkc9S>Vra&L9O$@!xO~=>%Mu zl=UBl3r1^cKo0$~!`Qo7q@HaV=i(E{iI3>%HoaC3ZRz#S z=s9h+ZP74p0av+C_GkPbml@+x2A@uj-IaisQRSiM5eZ8O+XqQbjUp(8sg<#n&8v2&6#ZwezbUHZKzJLq(=42apdbbIx_zXBku3mdMB~rWK7FU&xe3H#-Q=3*$8`H5KT(%AV^w@z$uv7e1FyNkI zYt0(YbuS+-`er}q)12+W9%i@6$|BJ=5$qJWnfWU{7*ydZb|SwB2#RuzADBUjZV7-TF)9E+nE0i!f! zHfs;t;JMANtW6qI6FQ*fDQA`;(-~pbP-V<4GV>E7A@$GJzE2gtn3l}sEtKNp>u+Kq znwfvx!I>_Mjk|xQy!s@Vax!XF)8f47*8EJL9Gjz}xBC)}bPgDu`b0LN+v7?|i`wMR zupDSkNM`5F3p1IDX>66Q4d;BtTFazFe@*`EwioyAO}YH-_c3gRgBpbulgea#Ge@di z5P%Q#AMh?HGjEbFKLMO-nIwQ4-M@oTil^^WIp{bv9nou@4|aUbjKbkfD)Sl2^*r8}+88nXr!O`CIJ zAlpj%ylMEWQ(Yu?7tksV7Fi@td4a%ySpp@z7jm1o*LB~+hr*y``ngTmXCv{&d_`f}2&QpIK7H)h7<`Wt$TgVRboy<*C1o-*T$*A(C;X`?T8-H!*jBtcR!Xfht-~Fsq_#q=x zITi58X;k}C6L1faaa$b1^d+-<9hO4ct_ztF2xY*bS~F?zdP!5Gr@LL9AE*(2y{+pT zI5^~gV^PZX3HiWzXTBe)QVq(OZrL-7e4&XptoPcI(E`%vZ@rYXn!JGRZ0qjjUymYv zh{#ye;2~Cf*=krzb-lieZ$U1^MfeQXANkC$?1?5g%0K2B;Z zE7Cl|AW{NY;#&-_x|_IYTGCAyi27RgnsHuO&{Y@ePf)GQ5q?$@8)-?L%|_wUkP~f7vV|wxYr3+v zUwgQ3?*KCm0aXlA*5Us0V>0=;yTKdpRvP8*6w`0mO8{70fMn$a4O5Hw7-avK7&ryatl9sKNgG!k# zyw%jkO8eQkI1tiims0c)axGOE=x0u67;!$4a(h;HmH{y>wXf zvNp9}i^8Dbn^gi`ZdMdHFSi2G35NsH0IRF&nl<+HUG?{beh1zPPMisMY3D5Uo#5CL z`aDrNGuyIOstjYYp-S(*LnHMQ)Lofzd!nX`KHLFdTi~35D&CDrE2sz-h zt?}uHKXTLH@yzKjS#$H?dgFGsD(Lf#;=YJA*9{`Fd?)i#5`*+aRK1TMy`5BZKI0W-6|>E2jWFKE^V7hc(SiJRdnL z%Jk{~3>StJ)`ttYZ|VT5A{dM7m$1+g7NSy;!cf-Ha+2FvHZilrI3ivy>&&V24ozCT zAtg)$3FWgIX@><$a*v#K0dQuwwhRNOuZ^=@}O zD6}ygZ^Re8HIUH84spLJV}`8dK@0%;os=fq_ou;sL$jA(lo@Br?{Lj{8=F#IU!-W%P`7>lrO3;?x{}_1(r8wF9=^)PkugKW3qR;TLKO%E_ zT$OFmb*ka$MYgh0_A95j_Qduy>Q6gG)J4|UKb@Y2Y|ydKqbFFF7D)Ls7^eGWu^;?} zCj21CY{S-Xb?m%)b|!jcdbld`aoVJIZP(pK|JBsb=*%M;p_9A92ClqGMww*cHf{~c zVh=^D;w?fM#6|-z;9b0oPkHsYFXyGUg}Md%^2_Okq_yc?mWj;67&>*Ydk&@0>Es_g z_=(^_dwvQGhtFr@huSO_O$MS;{Y^9cCj`_aI+m{C@PP*y*h_&D_Rn2+Di$wcx+82p zNq>s!jJw{?L_P$Yg@1=AcJsHSU89dd=1m*4GhJ^%9_5ycysk*TTl>qL4vNxSg5|kF zBNU2iA1iKSJygYjng}f*DKBkPHP4=KT|mtHkIW`wChdn^{aiQl^56%SxTO4x*sI)* zRpBr0rWdyz>q%ZjFya}vUvyfoESV|BSS-tX^qL4=#Qu=Fhuz4*XPM7k_6V1bVw@A% zOlhh7-9?{WhVsd7rD?=Nk?8%pPapa0*>s2ixrU4wK&t3L{9?rdxpi1nT+%cI7lu7g zg-=SS!7oi;zj27vd)T=7WND?`#AhvmHY$j+aR_PtrxBrDsQ30sekNZ zc}=F4hLefzQ{8yZsK{TP{T8%iY%>gwn6{5}cHMenzHg#1BtnvSZ#e*Mo)$B-J-a03 zB%KbwNiwg)5j_HX%4aMftVx74aa*ZXekv_^dKuC+Dw!QdKcAC*B<4jwgj21RZ_VmQ zG3*FT^SmMS0sUg#XwIjxuZ4&0O!GHwAs@qg6qUU13wm}VOX%i15scO&TGi0`_w;d; z&l9KDI<(@D?K}>Ej)X)R71p2b3VOY*wvD5vLooVncB5jX!`Pt=u`d@+8R*~{ZFsS2 z|5rA3^cq=dZVh;q_8U-vS2Goa;WA?mF5kYAn6qF@G%gs5!Xr^Es@!^~HHgP=TU1(4 zjbNng7UX}nL;{J*hf}^3#!oh8jIO;hQTSID3Vc27%K9efsL5xXcYOX*Hf;o z-+{8ci2<^}ox9!DYVL=P_vS9x_{9bEap0ux5EZh@Khun9BWx_VzWQ7Y5UB=VThB{B z(5QT;lF{#VR}j)*S{UNnLBq+uO4BbC$(}|}i~$A~6y#7$UidZf7v5n(Vt;ojiC`>C zic&Cdb8~52Jh2bx>5ct@>y9vXpR2nwl!N#b1bODEfyM~_%5(<`Iv5a}W1z8#lk$_z z`J@jdIGu}&=CW{bxIm+4^lHKvy!_yqbQ#zaPyzA$C<%ZE`HWz7_bCS{f{_LddjPr| z7IJF<1z|AMSBRtq1&O4oZ7dC?1`?w?6y36L5E0=a^2-|RC7Fk!={yEWa{(K45g~DA zbD;jA2#)P^#>3t`gdJMkBrz$z8KPboLALc$E#fT8)cq%M71;$8N&hM)v{Cjq{<)~D zsc^-&pgI3pj9@wrWpFBe8GCgY>Ajr1Ce9fY^q^mAjPLcMHNExKt6oiKv-=0t383dI z$?Ovm=SS1rL*D&%ev^Hlie#oQU@u^=;vpEXp;Q{ht&08!IR>sLGmvey{yCd8~O zY%whPHwu+Y0{N21E0;h zHd3D)zv4}7mj?=dEr~zlzjSytlkK)T!uJXqDJHcer9p=M_uC~D=8Xi1H5ZVWF!`Tu zjtmDis(heD_r6v4`*M*M%)pP&h5f=ekP6qs9!%Vr zc#Hp1Uf;IsmKmGDx!6#4t@~bUED#h!V0;-Tbt@JAj+b3_5#RDHcoq8MQRfSSZdT@E z(-lDm>}L!Nja0}wbus$8@m$Z*NINlr=fp=D7*B<#JUDxj=anPF`Qe?5CAUi1k}M@Q z)oG5pB)P5`MRExOTFCJ6(Xet_bF3H)4O5Q?&WfG`=tqO{54G51Gu>Zgz$?JZ7f~b^ zq1Yw{yu5@95TCXe_9DRA#ke_cwB^IQ)bTF#FZ4Le*av@<1kABQ2W#I&Agj2D`U*|0 z{{qS&{UKMj4b;ZzNxbwk8*W>Y^f6#$aC{h=N>C4IE)OZm)(s7l`#Tddr?UZI>FG6; zc(mIGylf2FZ{rJ`82JmNq)~c3&B9oOC)n$KoYYeh5ohH14U}}N75Y8&VGS0C6(jdg& zO{lq?YB_#kjk)oS`4q$hApf_xfaNJgNZdU2DRuSASvzjudtLEW^jQpej8`KSv$Lop zHk-jC2~?>(VAKLAYbh#{H3Jznt@~^;OMZxAobyCsuS~{mnHLiFjv! zOy~#WpND6|mlb@0I{WbEN8z3bBLb8ni5PGZ z?;P)2TIuvx#ju%WC(YfUhP@^lY0ZE^ehnwFtnT*%;(}#)wv*+=4zlx|!hepq_r zImaX7B~w52Ti}EttDe2KX5HfK z<`U&Mo_|axfVo}$_tVCtrN%UnW0F^pbwpkb8s36okjE<1mo%2as?>&jUal(g*>XGQ zui>aUIYq%X8}s4Yq$FCu%_N_fklaQvLaJedT!$uhpttE@Mt_Q9N?`45Dez4L%$)uX zr)IRh=saeW4wn;6v4*}u! zg(cwC0m3aKq4H1v0uTgWdcRWPZXZx;cj_XZ6ZJ|FRa+GVgbk7Z7XZo7$c+aC*v?C6 zWV+y{^}X-Al2Or2g_8Sv|L_0!Lg--(e7x{qfcua93n;~7mc1+gds$nl7f|*}$3hV0 z`+w(jVGMbkbCNDsjXvT&q@ttw|9z}Djx2E+OxMcsQDANH^#$#qvuONp!8izIV})^2 zbYjkoqLx>OR&KkC=R~ZzmJ2^^iMRh3IsVb^pJ^zZ2tlOD{O*ovrNSJC10zhLp2OJ& zs^I(w5$tv3`kJ5ywGCtjg4571wu!G^x|Ip(jil$o%%;9=nv35!J29&P_CqKHR?vrk z@NH*)$Kgw4SGc49qjt46S-YB}Dq@8=trvE0VPmeOg>VXHt}8Z^s4Rlw&;AKEQ6eaD zQy`!n3ON77AF?F}6z}a~Zt^usAOlt<0*#riHhQDvQ6B4DD})-C)OY8U9t#&6h?<{J zKV3fvufV_z1a%7U)Il-w>Yo_NGB`g-6S1Gzy+_n$eQ_w;>+S5|wE;ZACH-v%Kf?SyWP?D^imKg=@Cmn^oL~ z`;=%D=KBu%-}UYtSgyk!t5)gL6bRP1juWsc6qYQtD*~Z1PIKmTwdR8sSe&uD`M>KE z#nz}*>90VM>H;c)RX_`%j;Evkcdu_No3FG*6+)A~ICL!^d>r-owsKVX(+~3MZeCi=VeFY|Bn3$ zSu&J7Spqbtc>VdLg!V_e-Zlp5tJSGHxBD4`95W9~lK#J=BBUGo9K70uBvENs$xR#j zRG!L@KQ5R_D$4O9=F(d~*F?Up^uxgH{p$L_D?CIsIFp`*!^=p8n@=5U=>oubBaF?*8tJqGI3&{{P=6 z;u#?>t^1N^(El6X|04ogIgN_w4HFFVA@olR;_9cG7!qs0EC0z9{tJK5L}ih@D25)j z1lvv#Vskn}Nhq8i{NJEUd@U6|l0iRGhLeiqMWx9b-m&<3-7d84z4N-I=@kBd7YAWU zwCL&9U(T~VAIN>CNN7%<%7&#bgDZNr+{U6cmg_XtJ~ELGe>9#n;x7Bw8ql!=1o1MB zAjEW{E?M{zPw(Mf8z`hAPGt+`bt5T+R~tbWc0Q`_>IZj(-*m4A>)S0e7cc+jg`RT7 z`|tQ^T-h#0n}>=sVQDCe4RK)WZ8`XO#aId=6KPmzWy+Mr&guhYX)<32&~TH>~( zJ=cqVgK2-tMB=;G}GzlHuyxZQlz|aK_f5s1bBlYX?~C?x$6M9^=;g1XkZ=_kDLYS(jajAvLb~qqn>3TP3e(hWbWdC zM%LqD4=(poott`4HXK>iXslFxh1)BE-08@mCNQ z_geavLpbOvv+Fk#q_sycKSCC0yU_A+VQo<4hT0@d;JXf`PhVJ1ocr!(XcT8%P2)sh-Lnz zZN3r0PebC@8C&Au2Jda88SA0Dm1)1NSwbZ4-WjwXSZ?3Nb&w+%Z~bo|ef_Lm?+4i$ z6A_akG=jLf$y#PIC;HtnZ-S5~l;8FJ*Zlt-iTq<7rCc%}%~pbpX6xc``d(|Pla;mb zwZ=EeWn64np&V}-r~>gXX8c7=n40NFy2?0dM=#c81ufiuYhsedXylzZ1}!RXxJ95w zR{sB20iz^d87UmRYSk$g@|k8*Sy$sZI2`=~7MCuT!P)=!7|6@_+umynvdrGstB#3? z80Lu^d&TyuSF?ZUiZP({|1iZajj(4g^q<8`e-zScUmJcvzRB}F&`G;YiS`55^?N5C z>MQay3iF(^k$#7^L9JZA6(7;^ALjSgz!^$aNzyFxP;XZPLcAkabBNF|J*FX8+Q7n* zcp^_N2_7zh&`bCU{n_?u(__KtHLC8prnR#j+_cDrKydXt7|M=~(_&XbBW0w*O!Ie} z@6a@GL2*XX5X(j?sX{XK5FceAp(_Wddu_U_f5&6IP0>IoXZC3iuLiOF-qEZ(0maTb zh&dtCuT z_|Z=aF8a_FdH8h%SD`&lHtmg%`Wm8ylfo+(IqqZ12c`RUz8_l^Fk9>#SCw*S4`(`` zDZa;R4G$c`*OouJ;Q7+KsyWdVxf>PXY-IQ(N&%=y@lv&2`jf;4xQBK)6?^BfV)YZa z+vc8MZO{gudK(HZjWQ}MpD^Q=hTnLx%8Rel1_f_HRQL2l#2uJ=w$8 zlf``9dux~aR~it=4pgyg@85*OL^$#Vg0Ua=5f{*I_j|Bva{wvP7C;K``}_#kPWF;c z-eOcCf%|3u194pyMIga-k@0lksCX5~XvjSdw3lB#8LHp%`NPKUn>~mJ&6`Pn;S)Mt zN-OcF4nvhrc)TNuo-?lWnYEyQtKAh|I4(ve?4@h2WTzap;$)Peb1fe(bUBz>hTCFz zY3gRT_C&<;U!2kWZhR4|aU)~$jt?j!dEzo@xKmM8+A*^Fwc&%pldu#*Iy5pn>R2i1 z74@>kZKt%KROFoI`#E#=nJvd#qoNdk!jl$JmJMGwW?jQAd0*`K_9=aQM8v&d~3r58f!EiBE6N z&NHcJe55U%dD^Ux#X?sCqQ`#^4(^a-M(o;)1FlI`mn#aC3s-6#k7Z8g`4$82$oNj) zsRge#k4gtfGfvse)h9iudc|%pXZQ|^LjGaFnoi3*DElXe_MGp*!QEeL#$GyTr03$k zj2_8h76rZbeF3aOjl)H3&>es9>N{)HSN@@qRHqiX02wL1BAZL7nI~hZaQ03)z*v#V z2b0Do2mO8^RTOwx=^B>OHEXmS58+F}%{KGM67_XIGA|V#vGBkjGzVW_4Qzq+FXGDu z;F?QGV`(NJpz$aZ2b4;N-AissPl64%DCFcdd!JLCOFO5X^JrvNEmC0lk}tTC9ztp= zDGpq7W>H=aD29I?f_;4%kUA5mJ@FQFm4^=NT{BH!y{;T{Y>fl>9#Cb{@#THQmOQwi z83;u<^&i|0&hMN_fv@2&L-L>Ub<-K(G^we*r>b zx;dc~r0lw>XEV3LA)r$H%ls*?*hyUF`8 zXqY72$AMU;`Unl6D$%$Y>iFE{z<$xz;2VL_L}_nY!qxQ`38S+$L$qIsU2v48G=1?( zL_y8&p7F;bu6rM`Ib%Mtp?}1np%*~gO^1-%lB%i`RjRwCk61bK`Y`$;m7saX>*ivT zba)qW_jMh)G_MC{f~AbIJDNjPC|036yz8rst`_fuIQQu-Tn>yNHEETxQR-H zWe%#)-+hIZJ`{NBzAayuDC68Pw>4idM5b453;O_6i=d&A9 z_n}McX%FjA`OCJpyijrYyw}pySoRffz9rLe?tSDO-pGug8Yi9`!s?dLa$t35ckWU; zHHtUYiE&~>Y8R2=gRaBQOeutPBsOYfho4mPB8=vuVUo4$`_J1pm0wYW>8_+7(wtmD z%)Pgf*p03$bv;om#q)3Pw4fKXwLLkP?Rb#IJZ_M%AO4+ zQ|y~UtG4@dHu_)I6j|TH`k$^szC%6;TcIr6J3~`%(YnYKVUSESNH#3`aAk-R`<=dB zzGr#PwVtE<#9S7k(~EBZopy3?ExGyJ!`_3PE#v~vg{i_!sE!ts;@No zjN~ENZcoue7nR&G668*oboIxoi?N5%1vta`I??s%+7-d4j3Ed`J;){*QZBF*ke z4kGb>6Bbn~Jeu2(y5f{EqmejEgO%nv4qV1JAvXJ{JfSZdwXLbh)j_O!BBXaqyf%sE z=(T{Tuub~CneCle`82o@VXY=C)}papBWppro$TmK3sqAU9yV3@Eol73wP?9{+=PbL zN#Z8dlQ3XrxnE_uD5ZS%qM%x#Jle)J;~k2j9+UjR5y2?#%BTW-ceQyoajWNF%_eohTXhJZBefnD3mP^nY+!?Mj#JS9YhLZVZzS= zQa|9S)11ND<#7?A#Y2pLhC^q9y1;Q^&Sz#qe?*iWIz@{uVl zhP^%1CPfkBff;Wq>NBI{9PAXVSCqu!(6kAEbsz(PSvEQwVlGNm;i;h4ctl62P02Vf zy$``I{4Tu7Tp;&!>rl4g!oud8;l;GM)jGOj7t=u`Gu=*mJ96`7wGUPN7HxmB-y$Cx z#h^?yz<2+_H$MWCfF+KFX4BQ*1_f-i-wi4+`wd-tj|ek%d)Z2bTnUVWTE|tFtie3@ zZattV?{M_i+U1?INe=AO)w3(*@I~{-e5kK_Yz(MUzG}Q5?8p|$PhanpQ$2F*2h9kB zP;GEiBn6E`)~2UZONmZK({+bY!fu&~nVCwa#89$N3R%U)gkM@yy2)kb?-=q3tjlG< zB@SVxL=%RtO93TceOD{(L`P~IzH%gl+n96WF%;Oe*%AF7fCBWN#B$=xHkEK*4jkd? z>w)k+NvAA;yYMl)GYY0rD%a*Ywu-J_Ul7sR;L>OT=)P{dHcI?V^!6V*dUc6BZ301) zA8He3b`ByrK~%?n!(P^4nhh+Y+V10tk3aVzT1yX$vmor{K1}_d9t2X_n>m{ z0$OD8i*EdP#0~aosM=ulf?Bds)*X8l%7Oe|E=dKxK^UQLZ7`$G$d6QcrGf7RMsEnK zkQ15$YBI;f>8vmI3EH+`vTAZ9lJl13)ma#QJ(4p-7QOA>jm`GA3w}h2V33M48FZXf zLF#HR*)Wg^A4K3AfG@7&+9Q4T3?!U$g;(L52nl)FzUFEC^O%6_F}H(yijkI!i%VY* zw(ekssCBis15V~-(q#fa_&Z7xKbq-P_xMPGr8>i>h_36!_nOpCu<;ANiA9^`>Lu3j zxO28THv4M=IND-Y=}M4Qf8TB?;OALDDqJ3aJP_uh&XPQ~fjmI@=$BphNQB7Xwb3c4 zt0l$k)N;etE*Pw!ewPM6AnkJ1glY-fUlTG%KS{H-Ty?mdUYw&-@n%Pp#OV!;`<`uL z!^stX>8fOactQ7Pa8kNw1Rhe6zm;fH;q*sO^n|_+P^)7F!G$2k)gW7Ixqvt}yu{llft}8I^;TT` z3VF2cT`yv>sb-Ic-y7Xdg@3{`rx%PVauN?+gqJ!Qy{xJ*SEZnwl`cLnGO9!E?Yvw# z?RN}pOR!zwFnJe+D~4+uv2w)c-+{lj#RT4Mv~SyHpg;I!^hPL3!TY+8ly48p@)BWh)@wq?1`RK)wsdyKyR%R>l4t|Q1}t)&aXf@q?V%nDv|}sg z8=)Zo*}eEls585_KtLvlSQJwBT(ZyZ? zAU}L)Y0xGN1B-00%LtN?xcIZj?bpE||2lb0uYR^g$tI3bBSjMVSz;Sk(Vkv~40e8)_!b zenxnvIS(!*Yfw%-LEMw+)_h3!o-}?K9p6J^8?%$z^M`k8Z>anj%&ud_z{E9*c1hzy zX_Q$$K=FJcBE#ai0zk|m*HO&_78@a;hH)-D!Emzj&39J^i8lMtgTR(eWWM2Go9^@! zse+2PjoN2ifKj_Yd(4VDmS(QUq z+i_GBMPyvu!u7gbrcgG+wRE~uS~x5=Yv@?FHl&MyNU4(*Jr?cPBK`2ipSskGTnpqh z#wkPiM+3Byhm#rb_@#i9ok2R`4?poIZiWxQ6Z22+Nlue4>z}JE2Zt{(*X-1M1<_Jm zoYZN&HKSLW=J%^eJ|{n-^77B2LNAD+{B)b#2qf;_boKn;RRoo6mFCiEcf7d_w}0_C z@Y~Og9O+i9Rn!!7JpP0aJ)IPTGI+)n2Avy9M}k1rrKt_i&hMj94nq{GNdk`7t;?Yn zM9!a8rNTwL+I0HVI0T~tV)@FQwr{ zhLDvUB-9z2n%R3Vbbt7psWz+?cUV<`KZHYsbT;`rE%Zm%B6d3!U2sy+ zGiOgingY<_9#jJ*)3{Jy2|34J1prh-_+H<_<9^I>s_bO;nC@Epvh!h>hFS0BL9s*| z7K1q(-yVy{Ce6%zSdHLWwxh$_lDygC5?9waC|&__LzJ&PYuuxV&Zn^yaHr?vp#Rg) z7yhmIt2_rRD{NGlP#CG&{<6|k=fGqicOCdpE)|Ipoa%I zy@xVsep3 ze&}K^UprAnun{H=#lVzHghpOB@2BVveg-^*iYvJC(Bw2QNt%0z?m*#UIy_OLvq$ih z!M$lw*J}=zfIlqbYr!(pX~N!=3_Zv&?Uw6Ox8p{OSmvfZq#boKLfv_;6(lz&oeej7 zaw@1<7dpp|GUx*z=kdlJ*p-d{pi_Nyfzg<6nIEOS09{)Cjcadsh?==-tHOnf*cS7g zq~EaA*Fzb|%KT`}ru&U3D;<#4o@QJN?`RN~Om8iU2V&y=5*ugZ%R$5gB)FrG`YJf) zC7}K-&dJD}w)N0oN;(tHc$5J%`<}9Q89KiMW%gTsJC3}6hC4c8-(G3oeJ1Zqj_i3J z=DwQ_cN5IML|Rny=m~=(ME?7K#NKL%;0?deJbk>p;9829Tg#14r8Y0`VTwCVS$DHG zrofulQ*-cP!IMl=u5^Bn%Gg-2IYHI@=XpxYJpX9mgagWsdh zz0~@{7*bIRn_y$sEzpt7p7>7C z+ke-Nxb__%_{uEDiPtq#1YawsN{3(LFBSE@_8f4a3+nBmEG&*+Ziil=5t-1nz>Xf! z^2UQ7a{XeV`%n}3!f0si;>H;h7VU129uU53G!i-_#eD193f@BALh+WWm2GO@H=lO> zcupQY&%497MCDT9K7$-I*iN@Qg4~se>2E4P)l-~dx48U=DPIa@Fbho5KxELqVG-Z7 z@})61hPc}OJZ#WOfQFm~!YCO14kfHT+8Ch&n2w9%JaHekpi^YcP^p99{NN&VWGF{f z2o+HW>hO>Bz5>!S(uqm4yf0h7lA$4IRwmpOt(vv)eSGlH3%aMHFUZr&75O9RYT@EU zlr0nVD9|F$4XFRkb{#F^_V=g>x%bxska~SoQ`mh9^rpx4M?g@Ve>-ma&J3HN)-=BM9Jv4+rSoShIk*diT{be2Tvy&(v6mo95R$jXZ z&qYXV)gx!1vXnpGI4d!!)ADBXl>dz}q)viRlK4P!$hc5e)Lj%Dx);i0^ zP3Y~w+Eb$IoD|X;Ly)#)$l>*Gd0C#-jcHKFV$ScYNmT7#G%)=de!RpRNdK&f*N;~D z@KGz%x%JKNmAn*B|Dmj-aN1!T(M49YjP)c)6L;g+73p`CPhj;BBRQ8RzCdpN!Q(3~ zYkr|jc@Cpv%4@HDm?jxlaXE<^gbcVZ^x@lP*tmkeQ_3UEGhG?eL(fVfVcqDkq2gtLl$NUdi9;<-mc3fm8etU3LYH%;Fae zN&fr$zY5G;cxhvm_A`Ii_qmGf%O5^jKeD{)pQ)Yva`XqPuan6My2J4~I%ebSZHIX2 zv>#!}&P%pMCATS%t&sN8zOcZR(PUdKxls|>x|xC8A1k2K*AQ~>nD^Z;uFg0`NSMDd z@!#%PV%&fwxMi9}YpoljV=7F;c$2?XVL64(de=MJx;38l>jYQZE^6A7;5Tq)=*=~q z01=DUChWOWK3$sI5~EJHl^42_-3fnN04dHqYwpfJ$|GrIf3SmE$f&1?s^a?WVOwq? zW1s!*>7@dY(CyWC58j3eEy1gSTl=VSkBFZGiTAQepBh-&%2;SKvle4L(jU%V8VdGl z%m@E+vHW=P!^^Z+7czErtu@Y>Bh~IIC3g29umEiAr)P&*A|z?0yi)+X7q?$3=WfoJ z+J)-prOLkoYRT3sC16ye$&4-eo3FTG@fvrlNv04Ya>HwPT1Cv*-{IZ~)u_g&eGJix zWaS-4P&g(bV6om=$W=rNH1nnF6zGkXBK3#14N$+VjqRtRSU(QdskfBcx))fj3J>uB zEZ@OjQS|$lwZKxWEIoNIFyrVkd=^wsIFwE34#47Y{4D~xel-?31qi$>>Y63>{w|RL z_TTQ(UGWO$rEu2eP1J(LXMKoJ@x5IauSm?WD3DLmd%JKOUSsa}cKAK)2@v~xdjkwu zi-8^{M3`7k8*rgwV3n~oNO*qZBupRjqt2M2&|IQbf+Vs8Fs$6FPT>Fd@oK} zH&Z=coMvE4DnkU|ZL8E+x|Nb?*`dIT^xg~IvzFCsFH~j7Oh?QQKa7i3&s(<^#-NzR zn{6|(mVg-K=oht*>Mr&(2!s5s0@hL(>?BE-ykGjUusg|YGwd-O+1-2^;Jk04kqjxk3dPlDDCN=@qAAMU4^k|A< zk@Rll=Bx`;e?p(|NICf}@M@d42GMIK1Mkwjb^0^3;BPYroda$>)aQL4dhASYU-|Ki zuHiK9Qj3y1r`&>qeDs{gqtf_>(8zJ|5}sbD<42bU;yrwYB9*VhuLATN)Gw6UioZuc z{c}sc_dDBdBGXv+#_qO6jY`PBHILy!XOD2*`5oMRSZO}4jAHtLdXE}*?YKdAZtcIb z_?^^u7rM5PKEx-*n1Ag#wYUTPiK1HCbU$*b4P8> zImaC6y6x?ajw8mO`d6I4lB#vLZLK@Qwf*bfb**zck+DTEii7G-g`#_XmJFrCH9BHl zu9XK+UrNs4k56rGzq3+VpZnhmewz&Vd~SU$MqV!0p`gf+GAA#fy3Q<&+OIzDnbnK8 zhnz6=o4THClpLwSYBIA&{^g6?zH%8&*HlYpFf=Bz3oWIZZQU(_X`FT!`6&oz!idPg zZh=7FTcq{${~rW8dkp9o#*0{D%Fk@KX@D-CRCx~Vg_v&`O<;<~pFKnP4b^3+Uje^C z$ipvFZ8H)R;J%fe&Z!$>KlL5dqn)DRTg9qPn$69dmh-c1$Q~1S#^LR5+ zu2*Xh+(#7Gy>HQY_lI@73{T3m+`+N9L>99U4qOE$Mto3)dGTWp+_T z4M0EO$h7HtK^$0{{Wpr8%whsk+rQ;@*VP+)L?%?6_Y?S$ws?ZbhQFF4*(d$V9xViu z$&=ReHuECo@>;5qxDq!*c++cu zw;M4fevcD2q_Oza!q+B4F037yN2ZD{6>VcwqH`pngMV6cJb-G@nf-R&G!qU>+H=Gq z`I1UW4q;#+N1!lYpY5vhucGu~6powC9qn>U5b}C3anZGi&G(};f?4$P$=UiYq5cYT zZwN^{!>{A9&|bXDbmS1Or48u|_)95!tGO8K43&ajpY0zHaKeB}vumD9@#a{A0Yv{( zMtw^fN0PnRy4gwF*vGmNV%ot^inRg#EBPQ4;$aZ@+Jz6q`N@G?=F>#)g75b=kOz2q zMAdV2-xDH8UPq?1W3vh!=6PBDK~@J?qej=;^lOI=GR7jbgIz!Pu<^H0<9Y(Z{Aqga zN#cS3fqbo%w1EiI*4Nvm-(mG+0n&%;Y_O3*d-l)gZwg=Aq{(J!CWqI|q}tG)EthC= zR3dw31s160$L}QZzalksJceq^$Bf;jhyv4sAgz9PAp)9jm0)v<9ZQ0P35T?)!030w z@RHz8rrlYFhb)(I>MCvpCdi&6F9*Aj0Y~wehy2sKDA68L25#B5!(_LDI7*kHqsV17 z(T{kZA9RV@iW$|lOXa6*I)8d^JQ@A@=rD{Na#D{F!|MkjQjHWoQg0206YUrXypnA# z-wq{&nH!u&2C(74+8e@q3%ppBr={YC|E{hs47>pGEBP}iRAm)nu&LNl@2_kff`qX` ziS}_A*4!V2k!TT`euhb$ymZKe2d^KF4`na$d?^*y9BezRef;sH1DxZK9_*<^V!&*7 zRc~OwMMmeLDUqB_a``Zg%L9W-*#XJJHgAZoh1p$|OrwjJi(YN7-A1|g-HLO<3))*c zyk0FW-&@lBqS4r8fq5d}`S<}$CE&d)u3w3-wgpH@z&B6MY%|asgOtmVuOiF7pL9As z^5*-@Q}DRU>dZIARe~>=JW4HyMwDcqCbLc&6|>;tXsdgDgbNbZlxWLe26rsj%2v)? z_m=TFZeJY)y?mssfgW%01tSoeiCZRZMcf`HT?rnYH&@u`A^quHi|dODMVmL3aqqd0 zso#TdM?%4s>nKW+#upOb0u1){Ukj!*80CtE?~JP+w4ov1lg)~OaufyNRgcM46oib=uypEw2tK})%?#W zJv^8>nL;ZT>`7Thc|{jnc>x>yvpk;Vqvq~@tNJ5k+za{N!7D2ic7R12@zdtX4$->G}$p!`5>Z?5V zQb3<`$rddysu~c155&n=!$`Xk@TAYR)~{98pqUBzj#(-Rc*H#jc}~~h=~l`Xot$Vo z7pE8k{au!z;=N z#);FPPoKFe2}AB~y*{p34TEXiIj|Vz)l$$RM%Ee!HxQ!3{heO5UVdbsUsqs4WiB;p z6{_NduAsvDK}I{!6TnlOpWwjbnA!FAqS_1-}^Md0yU5NdqKs6 zN}NwLp0L_$F860-;iGdSXmx-S4rU5^e+6WZ?go=oaIe}E=>fLK%P;;f#9W?jo_}`5 zUPhD{XwFVsk#5Z(HeA@mb8Gb;B<+o_5L9?@+UKF3fhI$1B`U!&SE>ukISaj#chuJ|d!!M+tb$eQiSNdX&y7EJu~lF5#OvhKfE|h91_SHqoMWbpzco;&s9eI@nXkaz6EKKZQpV%dpX?zdQ zQSV(rxi!G)Nk7Sb&xR!`2ZGa1V`PX_omEufxcddU%@ZVRVO$6!zQ+|4lNg+Kur~h- z;K$-q`zGX4Bj5?k$a3mWG^%XG=;uwae&H!&Wogp^&qbx&XD2rFgV_i3ysZkfY(4Pc zy+a+cJ742kq~BFR)qlPY?M7U1Ihba3%1-lTU_t7(Su+SF-Sx2Yw$UNQi zDTsi1w#xzR$MMwg%jH-ESQ6*cp{7P_-VWY9WvXx-NNN?BhUD}aB*L_MMr*Hv{dB`A z>v`WM=81GE&Xp1$`uRHccfBENcCSG>^9UFkd&q>GCN`dj23U z1q)IL@zfwJtwH9!x{wt8(C;q8(s4iMuG6oQJIe^X^5WfX;Sd2-ybFQ31WH5UK;(b_ zE>3a^+s7em|5*2knPqzwz8rhSN?@)@qg)FldozruoJ7(Mjgp3*CNOmX3SqRevHq}*Xt zrs89PgzeI6)a$rZM-ocm6aqbMd2JuZV=3=I7+A>>I&)9N!5>4xKF$i=rXqdahsia% z_Si7Had{s{PB(fNr1#j$LkGb&$*XF2*>N)kpMsMt*71BN>5q-{+lnOkWqT6 zKV@rLYM!)IWI$lIL;IceX9kGmhpV!F>T)>(&kvdow_G{_3>gc2Io)l#k3A;eo_3k{ zpP7>=`BH7tHIcCjK3fSZp8Qq&JHY>T&iNUEp`L7m_P)|p;GmesQoAkxecfN%gHG-1rS(=&X%C$(>OLg5R@|<0 z7=67Z?G$GLk8=l&+3RWQemc9Y)e=>dAH{*xNPejBX^`{LttLcuYej>RD{q~bj|_Fm ze#xm^Gp-FzR^B$9c|9y!-}G8RDORIMCXDMCb!5-t>$2uq*?UGl(@)b8x>1GgrdEyLND*dj|F~f!w{an ziYJ6Q{pNB{)^7?vSliFRE0CH#dMrEo5+264Uz96n#Qb)qb%zoF1*U0ZETtd>dQ3nseO&I4K;K4S_5LB=?`h0KDNG7Nk@jk&G#waPn5?_Z2y;=NgJD@RqdaUeW z$qb|7R1BCFJ=(`*EI3s-KNePkU7Xw6$-7< za$f0lPlyoP?T|N3z(Cs~becn0fSC(9*0|tnSC(%mMDVnmbYf@4?KDS|VdsB z$M7W?Mr&R&%O`VilT$d(SeCr}M!N!~WPO%43KqwnRmMFs2;+)ng`6ZkjN4IXLyxDu z>i!?POj{e9$@OucVxD1f*I-b-OxAmaWGX2SjB-DJxH_`863k!VR!1Wj)%U6ZW{N&6 z5$?>@(v+!D=dl+`>VXBdC2D%Yu7b@V>PUkbIPvODH^%zEwh(XICJDw$ALn*A4&d>zH5Z;o*8>kjqmrk zRh%^=1#%-ksH56%Nmat=ojqd|BSX>?>3w^O7)epX3`M#ekxx!fBa(l4;uv50#nxjUOIE z35+KCV|Y#XZGTKVt}QhEjV6mHvU`gRRXTx2oY8)m9IHK(XBlR99$jizyL`I1a1(s! zn)*m>Q2+7mIH5aXo^{uXY>)9Z?~cbDDwLq#xZ^CE01|y7@nN_&_t-gcgjQ0S>{PvAQBUX|tUV8@EJF!XIX-c*l}`7me)BN>&2C2E z#dJi{r_9y)gsC%+)-=&p)0eNUR>tRta(zO*#=M z6wmO#eXivUVf9&1ckME73@-}N}n|4O~KN6z!?8oJoO4N|j5%54iqNOCz&XGPzOPs7W8V6>g76xwP zE9~ZT^NV{HRuupsfBZ58Dc&+-R3Trs$L z_!pNX?2}|7Ilyg57JPI~A`#?Mq+7(?gLxJ!;NsaOVTojV5`BwH4?Z%kmI?JMA_9!~ zmX_ewjmWP6fOnF2K`K&2G0d#*+lTtlqp1=8?tYG`KE_MM z*{>YxzJZt>g2f_5phMzu0QWY7h~ON_nGD3NWceZLnifU+ z;&x>UO0Ne_+ww*uncur(qr+)dpdpt5Wt!Qh*Tz%7J{tFf7F!iwE_;FY3DWk?>nsWb z!O5wvwr#)1QP-`5^2EZ%5KHEyFRB8arI$}x*rqBwx|isnD@#L91HqI`3C#QArT6CrSL${B@ibY?sUf=vVwsN*_PlgF5c5Wy$?sD`myuREZe_l| z$QnvjHxn-`j6Ox;;@6o9T_IXUl)u~tfT#R@@nhZI+ump?*n4-pf4WE{xU|d7F;ym= zK^XTVh$Fx>-r4zU1aCtgnsz*L@r{-r?ZSfGi~F**RbIZ$dE~lJGXM<_d_PD146AK= z*%%aBC=Dy;R1jtN^t~TK$jt=txvS#*g9CusoZSe%>4V703yYBLyMO5YiWW%L2wpAy z)es$|Fs95e1M^~q5zuz{`bh(%?z1j_CHcDbb&J?5jJv-%%?p=L6UM!Zt{$ROKXXxI zpSaGRg(%oqegmG@^!=s}_TUQ`RdB+rxl1`vlzs4&f$5Nl9a&p^@&~M1?|WlE*_K&= z0(!g(JQ{%LEE0F2p@(p7`H7>LIzF_MBdt|WCwsWv%;(H|8I9Ewx(SCzX}@~oF3&f};XpT)&?*VBN`2gq8_xP+_L zAMDbTHuf%n0}I!#p?bn4C0HO1eLC`QaFM!nh7R{kC8!__{*mo0K;u5gT`|j6nhj7l z2ph&pkDmLGt!V-|^P&2Y&s*v$u;S!*^vmw?AFH)^FXXCvEA{L&#~^98F+uFYkS1WK zrR_+CB7e~x6v-ND+{7B;wWXg5!Gho+5u~oRFNGUp#_RX&8d|FA*ei>`g8YwXhJCvF zxewu(&BgfU>WWa!pFGdSTQ5;ud=Tt^2IL??{S0DB4zc5Gu^#yHV7Xma2h9*8|FV`B z8)o9RVLYhg8N*0tLb#;s!`5tRkYMmf|E)E=Z|uOleRi6sIM$R}4=nwW7DA)k!S~LC zH3kfX>UVo19XLpA4ha>zB`;tQ+P$a_E-_2T@2Fm51y@}8tu3<=RdM75%;;Hi;&SYU zBvSk`D*VN=>Fa5vwRL7?I%}N3)p;$fg- zLJKB?IfZ+Y#DKw^18+{vjc>tk$X*R6@hC2Z5zU&~i;OX5jA{ut7xy4`f=t^+Hw^w+ zyODgH2QIu|1(}CEXvgSJ1%inmz+{;kF#L_igJy5Pe?x~&JN)sPE^#?wY)QUolMKz) zj$>Dt>QN(rp(8v$cBXNtmekJ>g1;91&bmJzfLjKlOoWf+_8?L+jwXR{9hI(H2@V7+ zqY&%;UTdp7WDobD1x18kYb@^+;kM}QGd)-=ZU@y*jOEfyFM@|p1UBK z+HERtGPMwMmaNQp#HrD2y)I0#O_mAWS<3qW!|Ov-;1a#NEB49gw4z}#BaO^9BlO=N z?*I69FkKwN0YuWd4^tTc6L$b6uAkK7tw4KRl_oQ=nJa|5B7z$!nvB8XaaKz{%3A*5 z>xEqE@zU4(&it2|!<^51vRv4v?{Om_p2 zT59jX^UDNZp{gQ6#~Wi2g|-8f^tG8Rbk3zd)58;GmJwI+94n|CAoe|_JJS2Y^h^D6m$=zIko-z9W-U?sL!sz@sn2YCK@tgaD<8pg5{`*wmC&XLTzDT9Ml`_ajCaSy zdAQT(dlvz--~-r6#&^P1D0R8M+srZ26^*w=grwx}Mwm!Y|6%ifHua(x$jAgjU{Wsx z9PC)I&^7(Y5f|FEKNXEZHg{Yq&9}Oqc%frI@L@p+Xb(R%IIaC$nga$(^Z_PQf!*ez zMDpkqjwEnWO5wE>MYKOw^=*?(Va4m8SxYy}zq#LI2#P^e5Yw6njwme1z7h;U`tX5 zHo&0^!)k}6!O`Z$jykJ%G2Z0Q`3`IQljpePRTTk*LVk%^$Oqv<9(o8B@nJnkizY!7 z@xw8|12HoAu~qD9Y;C=JPWKvPQg-MF&{8iGE%4AoNL{^t(E!Ng=h@VlN?fnL3PH<; zJGjd|=a~hV&wI0v02|*}9`~QT^`wLSc?Zkj3r@+f5T#y3BFoEPR&z1`O+T*HrIN2{|W1dS;0t~Zcqm~>`_l~v=lb%!RH=Cf+p_o)UW+VDAkO{-<@|| zfBRpc-aQV9c=ys`B;dUE0{4f!K-b{jVtPkPhGiXq4Cc-Y?s21a%%MCKD#Opmgkte3 z?S@wmv4D*V-e>7(I|=s5USqyFJ1cFhJ>3vB*KdyomlXU?Y+tXGlpm;^xVWs6H}YS` z6n=-^|Ea7L*hX)uT07rG$%dV6W65;U44gN+J%#XAe4ci$m*8fqbdYe>n??qKlR=e(T#adJ~x?@ghQbw0ia zQO1JvDC7xmpV}t?{cJNNjXfH(e(u%g7lZOK4uFE?c?Uct80tR;S z*f=sIHga_+&1(N7gWn`oOX!hynC&~%7O6+Y+O6tNMtS+qgb=a2ZHg;l^=Wlyr`p?> z?26BqRZ71rkRGQJ;1Biz&?uVy;$k?lAb(9VA>@N(>0-;7C9Z-`a1IuP85{N-zyln~ zlOH|H5HnD#4B%#x)0nZ}j$ObY_Y~xnbED^@DvxD8EZE#o5y6S}@HS`a3H8okxHVq2 zx2f{iUHb3C(k<-0wCw=H%t`c+l+Z#I>JP&O3`o|nDM1GR_;j8^sCzQdiIBs zXSOBmLj@TdGWmrW7J8h->yXw3_mcO;G{qW4=sE>dA}px(k-6b%swB)DzPFaPw0aMs zd;j*PLWKu>{8w8=KO^$iApC5+omdPz=vMXC-SSnF+*7v}Ro%^_xZy^wv-(q+qi z^2YRa`yn3=OyxJHeX;)Y+rkR$#rQiMA-eZJYbC~Kdvdlc5UpE&5Pxz%oI~qB(y3cW z5iv`^?v6&PUvIF!UL3v7ebrn`jpM1@l5@u7X5#!SsleSR@hK%-2~*(l6Q2IyTu-{)OWo*R^bc23f z+p2sg$2x|JZj~lKC!+pWSNRzOMzkaHP3nl~5A)STUp6m zr8^unS&|4{@w$53gi?aJyFq^PSR>#FyIj-vaSAKYR3s*hAtE#gi$9s(FkTv**NGah zPT2_=rul2=Tf!x;m7nFn<@zYKEZ%8)y%Q@9@+_N<8MzS zh4_3EgjM1EGZM7`=_Nkmn;7vR2Bhmdif21!3Mdi?+JVPHRDrI%_NyI^7lflp#J+z1 z-SBt1g+kIs{&wITNd(6w0k$DlG?H+YAb{GE{c0c&R? znV$O)hP8}%$V9-Lr5#(OWDq`JmVItM2A{qewnz~+ zG02?>VevN0td^e4X}GqaV~OD-%3PRyVLztW~F)k+v=H>k1>1O0OIsb2Ch``cdl z{TqJ5P!HPQTF~S}>6^H*cNw8_v7zN7i+%zJ-+M zo4b1Ke)0-_(P2y@$1Q&5kCh5ZUC(7Y4xCh+s0pz=?nMwN`h8c(jHubm6x$mZx$T)( z`!3A*&Xx0rmv6#dHjBT02?*DaVLwcey65SKDM)4WyLGRHtw*Z@H@CFai})Ha^lvoV zt61O9_d1vjY_oH0NvvB0;mN5S;;xqW&8zRdGN`?b{ez@*lj&5&Hhw=#u@W|}K!Bv2 z=Gi{@MG7K4Yils`&1`D!$ZqW1J!llc}&uDLH63LJLnA>hqbI&333H0 z08v+)H55@E|HZ>{y0^>*L_6|Y6Lv`f%MF=;C{K=%B9Y(B`g7@bBzK>^@A6g>6?pLN zzD^IG?T%|aF%O#E*xy*z%jWaFHh@%C?(rZ(sQfA#AsfnBK~ebNYf%p}O{n=giGi9Y1cEbxY}Vah_`Wi_rD3(9ir<6y zBvNt&ad}>3m8)m4M_M2#-*WcXxVa$ZB4jOpTsa*y6}B)0Ko$`=AV*uWK$eXup@Qo8 zJ)k#gquuR6N&Z1Dx5?+=A+>I zQ#2(m>-NMEt;KT8Q9VZ1OA*7YkoOx_-G~&b6{tIs{^0P58rbZk_YcN_Zp5ch@O&zy z=9{n%f3m3R!BkYl0Fk0IXyfIwL->m)RdU*6ewgTyo|zZSZ-CW2XTN8nYz3H{9kNRf zHc~=~F*Fu|_nq~}CsD7t5dW7oM!1sCZ1U!_sXIVHI2!?eHb(M7Nar)~gmEbp&zki* z_v_ZjhINa|3CjQBd zLy7JW&2D<5a~-Tj&FEsbw{(Ld3f=^Uv zt!A7EuUU@)E70Gp3Wa4WuiNvx2Iv1@BuNf_Sw?|e9fzX2l(PAB=K14V^#Vi%Mk%hj z?@-h5O6-&~12#L9s?R^A^(q!fvi%5Deo=-vApf~eq>N_fhUtjU(+EjfKKT#YMFxUp zaUgY)9^5y1)%^}i*QyeSDO{#1P4gx0NDS1lP{2e9k+@-y+|#r?rzeAST?qN8Pmbr& z-TPwK{0ZaI-^G14HeU(>!rb4m&#^*ay)@)cB3Fh`&>chB`FU_N|C(`P4F&(~xDLWd zFhQb(U0+H^&(QPsfSgRE+aFW3PEo==I}^tK^gWnE>#p@8hQ#L)#)MP8gHWQX-94-J z!$Z1DS5tJjvmUOzCE0pBum=O)U_=QoP+x;?cz+F1W|Gt?RZvAZpyy&M6vbf-qfY3Z z;6wX-@e8d2#K;#{FAP*3rof1BbeQ1#-aOUe zuKZP%y7{=qoI;r^XQ=s(;zzKx=0Z841tH(!TmwFm{RHFfGXkW6Wa(jc&dae>bfq*@ zkQ#mNcMB`g;NT&FSV~6A`X?nT)3GLG{H7YC?LhMV$u|Od^!O*4TrbajkNNF4;@{e) zBrPgqzpkkw!0eg}+xe|{YbPOT^0@!#>*05UmRcvu*{4{3STDy$;Up2-Rza~{F(={X zo{_X6h40OAnhxZMm|k`H|9r^Z&MT$-=pi>eIA6Kae#-EW!HFGN8{@x?hATl!so-8~ zvFX7ClP}?%NYypb+y|jRO8qY=r^SM_5=jU`3!D=t(eM|R;U7PMOLo=uqzKsAr5!JO z&8`F!h?b3miYQ!5?io8sxRL2MlnOrl*=t=Bx&qa3IIc*%OW@f(*vl3iTH=5D#g7RW zh9~)|>~5+Z_6u-E6BZ=IUq-te3mN2IkTc;xyKZ3HZJw(qh3=+H%1Hbug@Fn?Dlo=f z-DM5RV0A5Vcs(E94T_}mnAR&BD`Ifkv+m$fUqw=azUf*|RlLoa3n#MJOsSu6XmY>n z14d+T7YFiag7ov`bn50#?!c8c2agN;2SHVh$xT5$GDrC*f#B_ME-`(`Ts^or8}-aX)mXr-L#%uDtEi z^xqOyd+}&XTH<}P`(u6}>Hrp=e2&zW@W)L<%(#iTJg=Ic!MtB3C@#~qbp6T*DW@zV zeB)V#Go~>zujM_v$4Ca#X>bsrJti1r_WYvL z9UW>tZSFxlHHHj1Y#7nCS9an#azY|L%f0~dC(6PJUtpjYQIT)%#;3Z<5Ry2G871Qw zjGkW&-l8$beH8zf6OmEIaL1a@9=MRs$$I9x6H=H|X0VVbtsocEoAnHG^100bTNaiV;D8JbOcQGWdaCy9}FT6;%>Ien4g`$=H}GC7+=BpDGHQ=faNY0-=&wpfr#_Zpok@4UOKo%)(f8s z?8gk*EwIntSQ-U_-4k?zSiS;DsOMCEL29mWTffg$T%ooURF2TyE`+SsSZxj|IYvYX@J042tCE@fgq5&0{pU2a{YxXIDdt}IY>OyA@j zE+cXbxBIZrn?#~43iTv%1T zRm%UQ5r-R#Ii11NDgO&G(~<0A3j;eqC(@Hzd|fPbE}Cww+QwA5ipj*{!c>`mBa}S? zoRw^&%h+xc4-Ldf3cwaN>CKuVLOI{H#zJ)l;?6Kp76 zX5*U-Bog1Y!IZbu#*mcj+Lv(0XSMKGJA~8xdH*;OqZmM*Uu_UXrgOkH#X!(#t4Ij} zg+J4!9!^c0M$V0`bV1@~vI~EMC#P6ZW8qnq-OHCc$1+I&su!r?n$RrEKyU=DMJ|Up zFi}xi7oSg6WPlNppPti}K+d_hp1GZ<1Gw>o0WT-IW*74cLohE{$`!u|t*bPv!jlSJ z&u-~-F9&K>des(0>bupFS$h&6)v`k9S5VZE0y>n8kf!{^LX|)7V|Bn1ec%7MOH0$U zVDR_&Lp+1G-7BF2^#Xm!l^}4gUfIhUXv3rN5r6l^zbG9Hi8?C}wjW<+awT3tiAD11 zP%=Q^s>9C;VLzh4ae2oIu(vDpE~uO@`01Tba}*=HLFtpV0%cFcR|xn7Pu;&9=H4I7 zo_ARd{b|+>G6T{ZmC))9r|M~+WjvEsF~0(ZWvJB(RA0|4C=!XRr7p%Yde{@pOr$y5moucQ9+LS#f7o_N?H&ExN4HlN2+rjlq}tlHXiRfC?!hwg1ymXHnJ7d2PH^QOFfxkGeTjh1A%dLg z-dftIX(Y3k#B#U>ueoD3cIM9{fmyKp9*>-pC*LV`gG%;+UdBY%0+>^LM)L%;R2b-F z=C6FLY=G{*G17HVVq%a#7-g$GCcfPay+)v4H)v*a0r5jIvL6&VStQfV2**81G;!`( zS^9glP7;6_#NND~Zbw)rDhdCD>Kmv8MW!NMeV!Oj+I>nFsbx^$gLpravT3?+ub%@@7!gS)9PKLjFfeLa?Dv)3$8z zf>&RRb2*q{=Ctb^8mf^+ojdbK;Mldj;;ELvHx;kmn^Cy+uZBf1rEZyxl>ilkJ3wy& zkn$3=K*xst*w&?PnP>n`E0m-V#qF1F#tFVne|XZ8VXCyMceQ2^O-luGKf-%Kgc20n zNMd*F|NHy}x-_BUsnrkYWJ=p(<$LIHbv?X7&{Dhg$DJW6LAU@~NCg(RsL$mVvPuxa zr1JY$JPsO*o7H0^2OCXsc_>o`*j{hn3th_PR_h_dTn-x8^Vgp>hvX_=03*NQqIukN zyJA0P-jcN36`^y(TMhd|Kl~k@^J|Y6Fcd`~?~Ka==k!3wdL!@I9ae$EhHz-(;I^EW zfB^h?W+qhK!C;yeSIOqq>19xtoPPQ6oU{U z?<1{x&|Nc3Q5=$u)uBQ8rY^Au|apHC9=Qk!LV+-xX6hl!7@lEa3fU|vgcdY*w^zfe?kmAFdKJ4N7nF!;SRg{wM>{@c+922|- zmS}oykL7sIIq~P}cj7I?J?nei(kS3Ae|%;+LJwZu8}B{G*oKbJJtY3mbUo0e2k>X` zSBW|Bph%k{+M~bV)*+>qK1gi_{FrVooG4m2T7*-q(&3q^@`Gw5K)B-lgfiu2MV) zT#40&%*|JyI|%nL9h^MRqf=tP^Z-QW3BiA7!~6a?_5hqrcelnZlTw8-nHV60xQ)ZNSO6xB@nG%q+=BlTCkH`k zAHFCGB?A9Osfh5+W5V*@C|s721C!~VAizR@wZU}N4nF%Pp|tts{C^JXmq_dLdydKu ziS;8mNttk^^LQFF%^H{;2jHZpM+U_s;YY?lUH)4gGyFg9QazMXp0NP!yfnF712b5a z;4~l_B_fP2|s$DK}eT?#D;-~G6ogb9j*@K5BBcLB3(5M z;=c_={Jea=Gz26|a;L;|)-r#bzZOq_K39XzqcTwr1{`+)8&b%62!Hmc6g~q|dIW*Z z5o^o;0WR>_se0Rg{Te%D zW1c4 zZJvWuzdGA}eM5R1LU*9Y1($j*&DXiEZ8zU8H-B`WSwKmdk%s249YfM6bCQ z=>ERhll6C%hh+(ixqK5E4C>RRuy|31*G1zkZnAEMYwQ4s&3JD~s*hoS$PrzrCoyiHYcuuNPB&OhpSdke7iOc1rqRQ|2#M%yBPhPm|`UMWi?Bl zr5c>&v_vz??T-1K7Y-9gm#^y;3lUfg0n9oy#9EEN{NnmTG@q*OfLJO!pVBB+5o|s1 zxNKAS3FVSQi~3W>0q}p^z0X^X3YBceSK_rZVWe7{af;f5i2r8Wgkre|zfZcE-~)z1 ze1awFwg)Msl5Z05rFJ@lKRrJo+9Hfpz`d*Vo86rgxK-bycI!Yh0ctjA`F~6A(U9&* zjbmh2AatVG3WVW3hVYqeu_BmSCk~EkUeLHar`W)4#U{4jc%)n;ntxs0W2W9Ejo(U% zwUqn3C_vnC6Z)n4N+9olrT8F^N3A#Xp-J|DAHfn)AWWy`n|i^#itjVflGm|ELCF6~ ztS7`>iF^x{8e4Qs^gqN>pc38%MoN%nza_r^qsP9KN+n8`jkulyh5-FzK^Wn41g#2z zofmC9+?D@zC z_9g+opr6pTbI$FPp{{f7R?XYkq_~k~%fUBr3}$h+3zId8So;WhKy+LSvbwFV_REf= zy*ej;$?$}MLi8jjO2V0?eL5J%^-qE+%2}~pFQjkYac9-Zu@v_Z+D8g6ce5p`jp;>y zFnS+o)f*e@zx@bSiTl4&8u`^vDWx~}0-1Vp4kkU^z8B!`mj?o#QFp^-)rkZ`2C z88U{v@qlWafcO z)u@XO0D?*si$T72Y!X!^(YA2nrRZdV@1V%wEzeU8ofMUa%uB%4Jr6N3vbD0nKMx=F z*=L-&3zjP^6{82 zTPq+eYRscJ2Q;44NV1PLV_*G*_1X0_;5`hfSzzLl6BldCvZ@omMdN|4F&^as8%Laq zAQAR=ko5>5?i_7j6mn907;b3S_cLT5GLm(dc>0fQxQ@U4Y?yz7;!X?2=j1P}4o1&M zfNu+C(px_YJxe@WUFZWtXy&nR$=kiCgoy_L0A)x+5?YN;cB}+--Je}xpca!MuDg|I znB(LLeOxSd$8*++kTrFk9Z>aiq&2?As-;xREzR|lgnU@VA!1=0@Vx?(3@M0AnvwNR zvIu$Pm6p&We-U)lYUB8zYE^^fIO%3It=Um=8rUMH$^3LuXc%1va`PKol!iRO))=3; zZ_#`p#0yYi5=o=sy?O!REf3)qF(cVvB7@>F;C{j1$-AVnOzyZc3pj6{-x5f}+S`Lg zr@6BBJh(iz@A<>!xHMHJB}jh;0a=jC^IdWG-*p`J-?v#xDXTE&G1dtYW+Lth%{HRf zm(`mxqH-xGJF?h0KKs^n{+^N9D2i(odBdqRnkxnUumB~VJYA(;-C7FvC4*fCYvxig zQE)kPeRH_P7JdJdPL(1<8B*}-p(F$R&$h#(Z?UGNKUzH^`p*HI04(V~B^;I+ zb`=>A%sX$hJDjgd@2Z?*#s?_K=x!a({)!oH@?uH_pRI*`#>z2mXnX92rI2lyzTsO^ zlv}x`$M(sDmn!S0YcFNVLLY&@$N57A3 zT8likv$xwur=u7t0H5ur9~4UC&5s9u#k^%d#?ViV2S8G+ATG8Z{tPjz20z&EtYS41 z>fow>6p^NQO)?5I`uYt)C)m}s?V~`!+4|$D4b$n~PT(bYO zFD}aBz@DO4wlZQnCMq~XVf8AJfkAK6LJh}FGS4%&s-WGOkK^v*ZkBq&E}3q*YQhbP z0UC8>2_F0qds+{wvqFfaucqVM*o~~LZ=boxbkY!rUe|=)dN>Ks4klF0-|RMj1Q+QO zgAnIG-H_4UA=;jR_3{mrA7CZ?G()^D0<(%LUIB%(R!u5l$T1GI+D;ATun?bboA+#{ z=N=n9n_c%^25x>5??nV0NxJ2783nboh5^u4xkq8Tm8vBV%Y`Rl&L8IU(f#eXfBG(4 zPR5)8_i=wV+iPuQAvKIXnrYrqYrL~3M*WgxSJT-K04BMvAWZ}3WLAdgjoJP=qZ-BG zwK;OqYfJNk)_4l`BZ1Qu4+givF!gt}>^xB4yJyJ)CVIw22JqZq#-uGL5Dr?G& zZj#P}UzwU4$cDZI1-T7LDxb&T3(PrYoD$#VG=&pfbOXZmb^gb1!I{be*!y|~yP$lf zU;FX*+$5E^nxP1e`G(MYY|Tw-P*SM2<7lkbcGp$Gt{Hsx zrRkR?pB}dZhvk-=M4t#Rc=92$hRO}LgbXwCFS^`gZdzIcyj%cXayRo9>~rcdhXFQR z9QV8S7fovA{xlj!-U+tgQJmA6aRO6~u3ilqxT|7Z%jL>0E&!El75mYvR|}qk$c@5a zf;HMAYBm$+Cl4J-9mODVolHnix|L^L;gGT>J+$rc2zxL?b_$LiLsQnR)a*e?-edTw zE=K8F(>_)HuGIA2@h#5|n+Lhi*deTN0@nZWA<-AwnkD~FAcn9*_A2y;4Z zscz*Gj=>vec-fDaTckdRRcclp{DP_XSnfnKQH;VCzD7r+zDA^sIuYBidh~hgF}e5K zr71<-jSs(gG~m1Z3%J)+aen&4D_1$22s^=19J*qnqwj9?3d@>#oEc~gI@fmE74t0wig)^a{ zx5jcr`FKj;gMAFo4NUA1V|8#l_zh_aS*wWW6j;YJr%NqB1~5c{eceCK1wX&XCkLB# zlN1u=0aaHXQ46--L52c1I0HJwdFu1LR5rtj|6xcA$8>#iQ$#5lk2QhqGbe(Drz^qD z+2HVMLfluLeyZ$R)|=1xN8bS-Kw=Ow{p9n@VaUf%0(fA0>m|8r(&TL_6YD^{>peRf zv0hlfpdW1c5s`azdq7Q(E>4=@Y(s;+-uRG^+03-w$J$7zpY{Qs>BUqQG%;?_YSvC%AjrRi}nC>KLl0oT^BR}jIZ-l8a-9I zG!Nnv6*I;ASGW2upGrht$%j|8(&^OO&)pPp#rh`uk$ZgqsZ=!+;rYFdZbxHq>5%}# zxkmZjnFjB$M>NF3lD=pwKs`UTgC)VS7j2Y&g)qiFV8z7uJ(uUhn0v6-Rp-a%VI<-9yow?qUuYU1DD5{LVW01%_pU_r|xo+zkqgltiy zZ;f(4p{e|c=-&6Kx~R%pskB})4|MznT%@^v=(-Ui1LgFHWOj2-pZ;?Y^v8eVXG`{< z^uNGqc$26i=)W$_RyK{sSDRb}gF_IZ5R{o8m>AYXhp7T) zp+kDV*cRfS1^w61@lu6Ba!e#nOr-mp(9SES|t z25p2KQKUuvm{si6*M9(^zBS8@o{x}8tk+x9TH&u>{n8iFdUW@VJpRix2%cl<%#^a8jBNz^a;z9?nz0_KCjZ zJju^#3w#(G#8>IRTkoGmt+^);W&NdRVh?256U-)bYag?0d516DAU z@zZ1eU{catulT5_GOwadLqck+tD)))iKutKT*z#$(hk9MM4K2698-=@QENzbD$^^< z>K(M`;{mNe#Q!k7x1!{X%fscoWaqC_rkQuH(X;&Q(HAqokDF8SrVX>eUjibCq``!G zJVsCF-TX~e(IV>LTX39!!Tn4!$NR%YV&>pYw&8D?yw=I6xzG2JY8f=8#Jt6(=EVfa zM!J4OzatOKMbH~E)>my#u1s*!&HE`5nQ{>3b3qeq!&mFrISl@E$Z}#}cCZ85#ywM< z5*GF8B9jl=W6Bxg3 zdLbF|kUjO2rP&{ZMg@&=UY`bHiAqk!@iS>lI9Ao4~ICrK_YhLq3X}v zmLbM2&eahwiOBbg4I5uqJ=IZ2Kf073p~N?q>!mi4P1RgHI0A0Uemnl?hZ}1B6ce1q zu#<$$J+(Vp^^bn?KH=IyS?8YVXHlBx_wy_NcN+@>@&xZY-+2GBCCCPDnMA530~)b< z{j|LaTlt~Uv*s-v7S1u#A`}R^Z|2L}K2N5^@55l6%i$AP8p#-RAoY--lfP4NK;Xs0 zr9}7$G5rJ?DqZCFRod4liu5Q1$~dgR@3eUOqERi|VmXE+xt~J-BZ=fvpzsxAFK=8lJ=%D8~(S0eZ&6iV2QN^ePg4+0! z;CCK}&)eRr6Eb5fq;8VCj~V&p2g?CFvo1$~`5T+XCxU+fsssqza7yEb^Ajv(`(}HD zw33s<<9QnR9jNn5h}${=pofFH+{=dKLc3~4+VGHSJ{S*F2x%&1qaz#~Uz8pkzWJy| z^iBHL<9FhW@i^|IFK~=2#;9ktcJU-qboI6QeIS0M;1GsxW2j#)np3fT`EjnOuX2_!XC$HThCPlzKY1-`1qC57sLt_5tm#^ zD^3?=2b11|hzXKMOq_QhE6_at2p_itWvJeolIoKCk^}jS`bb5TbX_vI#$9@o;`pknnwQmxbrzX0;DX$J@p{iFSwnWQFx0c@}dCl1+Gyz7evN zbY9Yaq#)ICrv|2(<9j%C79{+jp~pID@=`28T)yYlFfP)iJ$U`fp-?Zc1u~@FmwLOT zGibl;ZvvhvP?z=$S|O5Qz7Qka}v_e0LtfHdbkONxzO>JT4R8WLn&z^+taL6Jl@Ieg?;C@YIGr`jf zA3$}6do?;L>tC71jzA%zo_PG_Zm;*m4$CC1(8=J;uxU%05Zpt%%! z_$5yNV9+5>+U`MbSG8Ngp#4I_8>Pw!mc*_wv6tpO3vIVv*dZadY78&Qr)obUIO!So zo1O+2tViT0H(V>)r{aLg1`iB{zoMqX?(fG=8#{tEnK=emV;vo^!o}+k=F`mp=_@S0 zllT;6lalHCF5?InMSQY%-8D=w0!X*$^@hj&L4X&b$7S*6l@FExi{he8rxOQ%Iwk2y z4!A~#y7X`|ce*RyKYK>_=CZR6ha>SWQY{70gBDI$Cwif&?gUbwA>&XPHXBh8JX>&W zZ@bB5k%TF8XaF}JEQX<)3oa3|@I4Li9^9N2d;WZg#A*-096lr;VAzhL{oQaBgSJu4T-dl2kMPbL(f? ze$3eOV8fJu1gz8hs)RZhnak`aOH#slw^G&fFs(fzVysy~PVR^Bq#FlTboK8weO0Qc zULqhfP}l4ywixlHjuMNt#`kYOTv(o+S{!?yJ#LO7?S--Q8?3@!HwMTO4pJ=*Ekfyl zB!lG#lZH<*(bC_BwplnDs{jXI6U_(QQEHJ2i?aIawhXas$ z%28@dkpr_BMJC~wf)Yxf$@Fcd-ax~ubTgZgfY0WCYX$q41o!RWu~Lt>;NLUX{}KV5 zMfrA(o%JZ@l7`+oXTr}j6&_XCw{F(%o(?DDwhwS}?Qz0^oN!7>vIph@2-vQ;7gyKN z5A2Jef}TV9c4leVws%Xue^B`~V#$Yi zjl$;czI#B%?XPTiezZkQiK7&}@2%uPOD&Dzs>YMIW6uj>o z!yJW-IA%3H$C)TL)F5COKR*+ zAC`f|Qqe5%x5oESEg)M)tLfI!I)q4uc2ZA@{G@Ju(TnXR2_d$kqi8s|%y?BaIxgyz zg%&L%_K;RXEDo1yrG=hs$+~XdCd_m#;2vC^42XvaGHHjEH<;|)gtR&qF$B%e@K8a* zN8%7~n?{-+E5x<|F4R_9?j7&Am*rI{8~S8Z$vdq|z0P~Lz(Plj?q*zcdF$>OH~2`h z!Cr}Db_O>|lOTq^LzaQp8v+`g;(yxv=c%o;i|A^BtFHeJLuq*`538I>Ilm!i(D24^ zqQ1%|+TPpLaeOjaRQ*-ve7VmK;(fx(iewO#f`pt1!4MHxNHwxWc~hxviQKO2m#Qqj z*H36BrHm=^ZU8TMt0JNBUzW5-(%R5Mdxi`!rNk+0J^Zt$w(TxIetB-T5^`)Ft-!M< zh_ahh{X?M@cIzRKzv2*fH~0EMz52fcR1b~qU#P6Y|FElz0;*IElGUg3uV!~IBV?O? zZ?#@temB9ShKtLM_#MUOfPeR+wzdGqNczUuZ@yR$E?e6^oeFc_uSNtL)HIAV#`CH* z-I1Wk)fQP_G2GIo1nY8)nFa+~g*v_^CZF<7r9GN2{Wb6t(`)EDF+g)y#b8Mld87M!jFTU>r}ZO%g%on4LiZ@t4+Cw>dAa6f+EwY-u^$aia-uc$q41spzLx{lC0G+knE10vJa0IgqDRC8lEiLw~ZRZRa%abYMW_H(V^# zt^XO7M_U&QHgh!GTU+-nc5gg#P-UF~;sCm=BB;{kgq&Bt$;2nK0k$6CA)jGjKR_Mu0>5lpm-dpJPU0fY+@=vEP==jnuwEI~-*F2Q7 zdC`eKrNFb<fJAkE^t2N3Yh;&wy=#zQ8q?rESi{$ z`_shwv=ia?YG>*5OdY43w;30W`G!ac3a=o3JtHH5eF+D4p&3XvDo#KvJXkX2DJLWx z=f&eiDoU*E1Xbav;cjipM3#TJ&rREj%?WHK;7&X&;;JXqUjIr>)XZG+s!(n}|5J}BtDwk8YT=8BETzc_Saw@L&*)tuCO7BW zbkpdw`ANuM!0ywig+~DX(0@0GIE|&@00;gv(R&Icdi%v+ASpMS&XVwvetH{A{lA+y zc|?~0@53+WzB96mTu=9v`5Zsil)c``bH%j`pgK0X{hNC4;*pHmvIz`a?2JnL1>Dv< z4=~|W@17NbVf4St>&L%LZCrP3To84MmP1VZmeDOj4U}~}*D6P_>*KNHt9bp+v%-%H^@dm8-xAL~!AgeXVNbyT=Z`#BHyr94L;gFn zY5YxZCia54KQ`~trYfGrv(YeSx5@M2w0if^Nlc~2Hyz{^;YcS(%_V#_0W9Ydky zUK|$>B_MhKdnB6WG&zCuq6o9)P^U86Orn?n*OOW5?N;qPs9U=7`0LH>u0m&j95#uR zd8x{C=#nSm37?N4M|0C?=fUZ>FY^_IL~JrQMh9DDF+wyV*bCR$;27ho!_$^ew)KkN z|H=dtM|#7fXWbOugXwtNRj`tk2^TiwC+@#=Ei0}bhZt4<3;4>~K=jZkKYGK(m(e5g z^a6LO#Id9+;hc4UHuWXKtxV@ao;fjTKm>!j2GiqPRr)^@UgI5TDkHp&o~a6h)uWC*JoJw38~8ddqVqhTh>ckLmW8OhYqG#^_`AI zZU&@_o)L~MDN*OD1oM4^;IDJlS{{av)fR5gJsiPFhtayLob z|8yc=Q2p&hbZucg6PMkTVc$wtfao+iCZnU`X^ib<`6XrR!oNEIr$52y#hUWBKcQX$ z+`#~+3bQR3hs7Co5!GXjzBU0jVZRmthZr@O^hS8LB_!*0Il_=Ho*K2zmlXSs&uH|~1%N2N?zPJm|w%;X+{TO4#HFC*Kn!%{hT*?u8tZ(?6W zbxcOT?q4Zsm(Q1ix7ctA2n9O-m*a4Dp63zliWQClIA+q@GNk$7m?BF?q;ZMr*xI{@ zmt~6%_-l#L2b_DiDe2Ygz#oLiwxc*+_M2b1T7uHz^POl2#hZSb2e!Y163dLi)g?DW zXj2|5KqzoYub!SrIErcFKDQ~{5h!}9-1NA1p=t=kx^ZRo|_>9m)qNGR|V4|&M~n{hf~LQh+4+HZR&q_ zBJG;4G#o;3-$Hv$SjN3g$r5zITTB1)5?HYA25ZpeX(6pwjev+MSiJ`7c}uB+jC{BE zhcA%RUfKa`UJR%7HOEQK28E|*DukW^cIenNfZ$pFBsT2n8~YxHN>qQMC;6ziGB_)| z{a7oF{TJ&wcJq2hA5bia@f8FPpee=sa#KcH3ZmlA{qB7=R>=nYB60GbxlFTB{`!<) zZP|A9?xo^(NB-&2T1eo06R(y2I{@VlY9e0`=&GQ!H-~#oaF=inowRmJP)+}DjM9gj zE9NMS8=#YFa4N?FD`q7A7_5bZyr9V}i2FG4{h-lke5&sDq!AL)r`SGwcsTB%$>R8A zBScs)yU4kgL{g4JWm4i*@#&Qs;P#n1o(;vcwX+njU!nbl^(}F&y2oL{wO}EiNdARi zo|d*;$F^+iZf+R((EdS>EEb!5EMobztl zP!R>AC}pC=x__$!2_UOo+cG$StXf;LA}_q)WAO>PJ~mbc>>~4=7#4Sto+=^(Bl)BD z3ayO~0Zp@Xt7*Jq)341EmIKnDlL`Z0vOOf3fok@7;&Qduj${3eABuCpu#Y`|b`P)Y zxy|gqcp{6g(NU{`=%}8xXRg(FP0YKPQFFva<%ydlvysudFby_v%z$Gverx&A)9I?? zJn}wgePkwW>qKv3c2N#^f4}x&x4Iw8&$?FWd9Dk~+%sA6?cd-#7KZ`N5fwN6*pT6s zW1S5NEM%12-aB-pTC_)h+7s28Aj6Y2o6KhCPV?gJ-v^4W$_#sl%R!=N8RaB81W4oH z)7O>#2$|n4Q5d7_ETg2cSvtCgR$rf_WKN$dF8}e?U5t98$^VP=gy6?<_1Dkb8zEYQ z%`|rJU5hCD{Fq`5pBG+*Wj48Y8e6s%9hMLJTr+dRKJah-GBD8&gKEvZxZ0j;acPl( zl@4bH{P9FuPbPi$txI{+Cggza`TIj)4tNMJ^N-lP$k+N`c5H8>0?LpK4G&V?MR4VR zaO3@vxS{gYFoyvLY}mi}qG8u%Q>U*exIYR@+Pr)|1%Xm<8bpOctv^|A@a?qBNFDfu z=BN}~S9eJ*wItkF2z|0^{w{Dk6We8|%tko~ZmKNGL zk`Pd@JX5t+H5sXRBmGjao#*0XbAv4hvTZXgr4rQ|$8oADyB2AB8;|6*^T^Gla~J;(&jj;AL!JPx@Kyo?ZK!2f-#H{aaG^2;V||NjES+kx4C* z65ijc^*3hHY3%3pJ~G$4n@JGPm*zuO9%N-f)l#MsNja*%J(d2#07R%lyg(4C>z#|2 zBTWyagWmlGM8J!#cG~XP=|sF5N8%!sGkHw#Qz~3tejMi8l#~N^PW*e<2<;!VYpzc^ zYDtzoD>q;?GCQZKa8A`Rm`rQt9V8=ae?E0TiGW%RV2vz|&9AZhkB>%{TPof}HoR;i zaP;V_#g_nzT*0%sMq&GRks!)vVLl(8Zc6KSA{O@u>fPRZ6bvqLNJ4-af`FaXR%|!4 zx4v4MZf4|O^8=opILM?C!uQ}&7;P3<3|O|eAoeLPKemy%2V1jB{tVSZl5yDVD~K*W z*^s#l9RDWS2q9aZPQkn#$~6=*g>!_1+}MUgzl10|W}IkefdLEt7C7$+oYVkCiF#pA z;K29?FT;Q$-g2!X001Ch12PpL^J9%>==8?2!g$*Q)cFvQ#ycqLKQX?rT5#kTPPcK% zn1cGa>ZNWrnDZ~>_+8mlBBQd8dtZLe0)tj)O1W1}@^ko>vv5MRA4fLigX8@Ia1@RpJ{xk&=4wA zs{MLqCA?GzrM<5-90Qz(2L%#I+dS16;xUxcr3D^?2j{&S;xuVEi5h%59gs;38#1Pm zAD;t+yT=edE?nU0%~hM2_c-xqFcd_YUY{q=gRLDnY|6cVLs0LY`z$hXC2i=R#-DY8 z${OYbCHlaNyjcD)9-lSkhA>i=np@DL%ZD)viOs7Qz`@+VfS2(4isX_|%;#VL>=3NY ztCN{67Ce1A;#-}h8Ya@<6{IQ!X}8ehIUkR>N!@QuAovIU0`M@r#>ur4HO>T8Uaat; z_aJ4`ansuKRrqLZ^WbJ?*p__%IX-Y?{_RgG^%P7X0C;|)%L~9cqRNXu zu#IH?rZrJSei41&pj8?AbdhKZCpEil=AVJdhv7`6L%9w3%p& z;lu5sx=is{4+TF2KG*{1Q_P3gf0imn8Zhi{$rOJ7T8p8I2ONwhcL>`BWF=~ZVKd{eL=3;QV!FhbtpHGT78BaI5{nk{b9|0t>HwcOgSpK76`{q+ot6*c2 z`KsI$jw~-DNB$oX5rrl>4RhWjvr!94c!? zRyQ=zX7lQ{c)Yl-J+p4(UP6USr`vl?oK)`_QT(^h?zl;Q1dcD=Z$qgK(KGsargLy! z;ujg~V6ZLP>ita_Jzo2Hr|3He^x@+*1O4F=z#P8%%v>FUy+{V#-QdA#TY|* zl+kxVXz;_=088YuR16h=pM#g&)1J|Wokiq=|4``S5Qp8x2O%52nU~n4K&vNf4uy~C zQHsco@O+(Ng@^$E0N4*0Cu9AvNM|w)KHf(eBH*0t;(>ub_j3>)COmpjOx1wI4VAwG zt>hhN6aR_Zco1-nMpcU^akH?%(E5AiZU9-`os2shGSn&cI;__0(s)Z0et+-*rjJOo ztr6}!mddCx&z5`_T@E8mgMi2YotMDsRYd`0;gIH-Duu%#>1Si-C++t6jB1*&j|O3u~qX#W(CEg1wRH|5J?}>iM2vEf(Gg39Us~+ zY%~JrdO^YjQyw|CYB_N6#kl3#;BF#N7Fd3;kxV8?gbEw@BmnKLRrZ*QCXPZ3RPFBS zMadFHU?C=)pvNQJX4VILK?<0rFg8qUDl2ajqf7gf=;B|$%hE_G`lvE=vTXtC{D8;J z==0{|=$CNuUqw?w{J}pr-$6UyK|!F-#zHXYEpTcdi>(L~#z|}bQ#cTK&G^p(7Xvms zS?P-%2~e1T#DFf8{OWOQ1h9&TnuBih5E(s?SklOdQ49n)v!IQKD58PWCS=uzZg>2G{Xe6qq&p?hQQZAN7LPh!hl8^%DOuW~EhuGxbvSF{RSNOQzXAq8NR=Y)-i z%r0o4x6!>Y-Doff^ic}h9F72ijA>n#wO24epxW)#hO*b}O*gCPE8VMA#m|ggy)Nq7 z;=suo%-d;H5C8`Iwrc?Q`i&XV%d9CK{9}2s`p>=0eMb)-<#=#djK)-|x|YGsM(;e9 zA}}Iw_wlmNagK^ZuHPKd``k+ylbe zcn5UR)bd2-)b5vOEyoUfYUI|qS2eE{Vi1O`RDk)Z%e=hmKPw$B`rR}3(M2f+Y@&4@ zjH}CH0V}O(5l4+^I(P1)mbS1^*8!pULjH?2yyF{!(I9s#Y{>oM)4-)6%~gj*3PNtK zHI(pJUNK**EMmmV4-Yl2odceQT*)7N0%?~xj-B_ejg>DGjdpBoC(BZ~6oxa2Rzg^R z*aU_3N1#1U7&4)ym)t_n1&H?3v6eI7xXnlwdF8=@Tko=L+dAQwvJzRB>JqoM?n+}z zuPniqLoK4^PBkX&uhnzg#hu{l6ncVOl?!~?SUDHb;c>m&GjXqxz`%@5;l8TpP(JmG zEj(1qa(9H^_F1}XER*BhKJrgn<_JtLwC2~(Fb^@a+Wv6WDJlTeK5FO< zMRQt(dKG8>Ot6We-@d`ho2Ne^t~4xdVlIEg0NF6^<|5pVJsm$QJ^r*Vvk`VDgM^|j z8T|Qra|(|E=&$EB6j2#vbLF01_ogu&Ty@huJDBh3z=b}<)+P#9S6)X^)XlZyA)$3~ zmC`D`@X=b}L}PSfEQ6PQ=?}GcPw}rp-_zmNz^!9cSjNQhNy8-wCNER!8~w64E8)yN_ORq zM;~gMtfG)XVzr}_m?B(;e%L4xnlKALs)wMEW{}*j;xB3!v;0gP$LW_|g?%{sm?3^7NAGUb%eefPeYzvW;8uZzUU+jkx+ejP=cRC4bU&1zj%FMeCW$? zO)M*l6J43hyI%wuMK;ge9Zo~$8mUqp?bkG#d;PQeX&WmQuCoUT)DiO%fLv7=tbX_5 zViol3c={fo+TzP^(XEZ)Q@XG%i`=a1a_{tJG1y z@Es)>fpRZ0IMzeA?jT9U?hy(1>S1oB?8&e&T?(fvHswf7!K#3Q) zl|$HrzN<`Oxh~tGFt+5+ecB;ca}WfbN0=O*d;9G;LCwFD$*8L3X}Qax7C>sAr#|GJ zNy4l7S-WWbQ;Oh@Mgq51*F>m75X$)R^&8^bVmvVS+5L{|%by0WI!Q zrNwtcgKn8=mwy;paXy2Rl|crgbOP9Xy!YtWRfJw}G-G}Sha#k0a6+Z(_UGRH9p%b< z-}9fh#Nnnp@6 zMcKLxRb1nnOey)6)Q>*s(!ivC!T}%P2Z{=>WdFlWcprq1XVnY)fg1Orfj6{BV*15x zmjvl`8J*p*DSylK-<62z-PSjvD6!A7SPjwWza&PO<(lsv0Ke$%|5(8Kw44DTA%^?h zajWT)J<&CnNVc+Kb?Dc#0ay$E)u{)fWp1eWg7D8l^zJUys*3zElffgYk z-Z##Ei#;x8KF|Lkj}IdyDVml)G#+;X&MN3nDdIUAx4%0@fwb2oslQY4##sf2fB((F zlw+PPj&nnW2e2xRt3KtO2!^{(sr&rka-jh}VD-IUi!bheT`i>fIf=h~0mGjyap3Zm z;SG-@<*km=Z;qvzdQo4JpYy#QC&J7Qv&4RRxe(GmpJ;)|UA}HDYt9tiuFg!ox{HTm z<`lDHMB*}Ar79aA#MJJxQ`o>~v(Oc|XyB>Hhr%qC4`$U#w=(`5`>C6Kx}H5$&WAle zE4X)0mS{!B#z&xRVFY%5I+x$%5Dbthi&(~T!dmESP*dj) zIV?pRZ>4(#rSyur3~I`4U6yaH6%S$cZ{C)2Hvl{%mCKa|$_@NUTurBw_#Q1{047$< z6(>Q}JfCkX{QzLpTcUPv#hoRWW%i@yJ(+2zaahGNipOr+FHK2Pz;BQ}#h6035|Q1{ zRyoj*lk8)um+Mkpmbcrlj#4#NaW731x4Q_0Tf^p$x!dz1# z%E|=^l#_CHS3=Drt9R!^>B4u#LD-=1Te-bwD9k9dT1zaBO}rYj`x%PPrcnU+iztxy zKjRHNLH7RLhIn48W~UbH%&hSpfKx%dqjU!ZBBB9^_q7uRNY`_R>lb&tUH+0%MgNxt`7t3)-+6b_syb1}%szA)i$T>9hw z^3|l&99U&t#t^rArLxvg61{cr1Ov5_d}EesOIDY?NM;=E5?v*er_}(W_RFk_PoZGI{KEaZ*^g%_Eor{Rx63&kqS#rf&Q7ApY zr++2m?_{S4{J@y9bheZ7k7iW3zdysvB-K*Xv52T>T}1=rP8|~k%>I^4m7@lDv+Epm zkZY?SIhLnbx5G$rgGR0DdOxqRTe(VNWycmKO8upVGv}%u@+_Uq2*4(%)r&aQ@rfv- zH#qVUl!peEkImtml_mfz0&8oLsG5?#Eevr>v0n4wgXO&|gH?m+2)Wn8INYIBZu9Ac z3QI?gDTXL7F-d(XOk)LU-giEJ_1G?^3#A;@PyJr}xw-dm+EKxlQ*3TdF?|?z)j5*O z2z5j)l_XvI+z-07JA-8n>EJKg8=|zD%o)zxYK zuFGHcr|f^1oBxYA{eQncQ2ww#)zQ_6n5JlRzuJ=m1oxonlSEq2dB-a2s{t6&Fs&Q2 z2iii4lFGL2UEq$Rb!W)Z_wA;}AGL_-l)JOf=4D>&$o>M|HrUaV>CBw}F{kV`x4AJt z3v=m}-dQL&TJZ2&NW{Cm^<(y%{)`292h52yF2b4i8GGj9ww_hWVt7OxFMT^M7 zvoi8Olqk{-7e^-vN6(kffhRsrE=q_1*J}=C3v(Nj|M6DM z#0BU|$;rdbciUCN!qw5;#moW)jQg)Qj&3Gy7L?C9w7i@wIMht6EJQ^93nf&WzfqF* zbd%LYwFS_V)#Rk)9+c;)jTc{7upa*7GI$uN@KHBz`~2$+9>)a`N~)9M6lx(!?Ch znP%N7D2F?|6Terzc3!3X5qKqf8Q?SAB3VY;BlavD^r$a6{mO5oG4}Ww=`aGvYJqKJ zIB{T{zxvwqJFT*f#x(<8u&cZdFRZwqxzDA#SyZvAhEsmc?)SRWn}odLj`2&@?${ot zNUOG))G~-9@p@SG>y_BS`O`0q>@nSYEAFBGMmN7%hri?<0cT7487{Vmjsn+z{c2E% zygF^FgE>OWm17Ima+hMa$-)Jyt27k%2K4DM=`Z}~t;x+)(Qz;qwO zn|IVgUNa*2ax$;L#YQ9Do<(C?XH{f6Awi3tO#XG*S&#qDrBLQI&)+nodU z@eCmX!hSf`p5jnC*&5di`$mV&{BiP>qDWIlhlnMvLl3+UUQGf=L;7S_^DagfJ&Ydm z4)to3?-kG0(-ujtDt12&cc(OW&i($hAMCIoi?Kf4GesEyDZR%e8CBu^0~3c&ct)Q) zgnQ_>o2O_>nXd9$SG<5!S>Pv!l^8@B6Eijk-m+~=s*Skj6@ zo}2SbaE=z%WPXApTKFxe0tjAwa6&+dba0(KY?2=@EtTFh@2;MT?1W%;u^Q1<^wG!% z>PtT#;HBbqipnsiP7|aiJ2?69TOrQPBbJOd5(`V0WXM;`Q01wuM8BcbV4_ax6$Odg z-J79Z=rhi)r+afE5&~b*|7=v$S1i9h?GN9w^DQpj+vy>>d8G5^lv!lBf~xd7Le5XS zt3G1d>M1TFsoqWBjI?)m-2X!w`CLcO6dVWRyHfi%VQACocZv_j1*)+*N~$8R(u_kT zxXA|%5D{QQ&lkVum4*hPDbki2_k@n(mrLyxg1To$A*84~QEE5kUbl#|O}c8fZQ!(U z!}*83Jw|mb`55`$DqWemgoF$}4w1yFkL(55j4iWOnKpeAk+~wLIrn_kwM2v-zc|fh z_0;wzun*T0q`ydFI*wNzlMXbQ$gX4=JNaC^54XkD7ddC3X|oWo9!eJutFWgPJu9KH z>!e)MXIRapl8j}0Z8$h9X&HrIMbWh!&3oqBG{=q8qdyn&`1uQJ;V)19`xGf~a%)1f zTFzU&qVaRuek^yz&#N5HC*gh6G;5P9P1&b9@Vqc(-(*p6>GkNr9Y4Pu(D`Zmf}U#X zg`l*~Du)J=xBBO3+@lMVa7zF0uJ7=~=+o-C?eEprIr_@%KPVtcCi8fBHP>PMw4K{u z1C*-hw&*Ea{qr*lVowSU%HoZ*h%A zJ^Th;R!x{?qq2vR_<I?d^l&llq|D&M>`E^OYb>8a;&e9PX%mr>s%K;k=z;n=>e*(g^yl@eC$#OA=; zl^rqld%A20=k)E}_3&6nLuqHCl-?ZSE&d*rb#q2@#ne7YGQZM|& zh`qfml-R*mr1A$A{ODW z?BhaH9ri%pU{BaTD)F_{waMx?2SPJAj3qJ}`>A?!8E-Rmi{~NQoyN-XX0tu1iK>Nx zM)){dtV_W=M(qcWxSzBEReNG1yhmo$#kD0xN@MQOJ8BAtE+^P!%g9JnjN}@f%ukbK4uA@`;nB{c6)kg zNxAy{`4yYwsN&c`iSszy<%3mGqXR>uT<#Usx}G~+U4{q2qm1k1#)lanG~Sl;N|Ng8 zR=O6Sz2(0?JzQcoyvHcXwVKScLO;~sSAH546CCbU=+{QlPNmlfzKh2=`NX*F%7=0k z!=YX?q&zA-Air^ZXt`{AZnWL*O5Nc7*n@@7&~d6>x`Ig-a?i!oI17fW^A?Jw9lk7F z(Fgbspbnw?z}1xBzf}4)x&~}SS#tUNy7$I;<#ZfB5+1|Me_=Vj7uf{6d=-S92YQ5N z;VA(5Ht|?Ekl^5@WcE=TK6YN{$Dk)`Uy)zUy;_8?+}4z=hQkqY`si@m@Hm4t5%Cm? z+3Gg|e7_%K@?@qomnbWR6_T*>h}?;0e8NbcVS$cKX7`PRfSuM3Z5ex6{9y6U)7MTv zda5%SHciZuoAQbZVQP0{w)7|eyzWx95|8oJ3VxwJlYIJn=GUs93HzDasTJ<#$d`y4 zS>x0~Nel9?ZjZI&pW`O{#$2M_NDjy+v4jdfVezguoy{%J*|rc&iEeiG-q~N3{as|X zB){!uW@ zymYU!sGFEZ8Y2dz#f7E5X0bA4FqYHjvBE`B+cy2!S8T0`+?Xc<-iWP9n+&ncs!1Yw zWKQ=@OJc%&btgHaX&zC9q?Fqb=F?=%f`oU)mE2h+)O-ml1}vJusbJmn(nnLzUh$j% zALiZys;zHZ7Y`0CUZA)ain~inp=c>y910W(6ev!xv{2mLin|wgQo#vO+@VE6aY&#L z8sO!3?z!ikbN}+*9rwO5-eT;Kov_(+t+Cde^ZVvpdul&=T}5^8mXV_=dT#y0JXvKJ z-z~0F189DCTMuIghr36uK9t!6|6+dq%ygD1dlqzS zlTSTEnD6+W4uBVI^nKg<2|oQhu`d5;U?ZQVP82?p=YDCBn|rxSdGMpBzrzr3dS1&!68y=) zU08yysU|R+=EPRE;hxavZm0I)ig)Fc-j{u^wUbWDQ0(GNdwtL`> zr0f4Bu>K*b=h5SD!=6hufhJVKVh{Fp2=FecHkpenMF;hO`}ZIGX(||kS7QeUB}*b( zRhUCFBWrnR<%jq?XU|Y(CQk-iY-#)lTavWiFEo9fo|CJ5Tu&XKWg~2}80(dpVuvVy zYr&JZnmy)qr2WQ-88!~AyK;bwLYFYLYFdsnwow#z4_$J&p+JAY&T;w6I!mlG!rDFI6#muG&u!*HnWI1#8*+yQ)SEd^t~91HQ)Vo341mM?#X9!TOny~VU2X{e?z*q`=tN+lTu^&!}L)0LP#JT zqfA>)ydqIT6wc&Ap!U;BKK=lLW2P6@UV==Qk(?jptv|CxbAH?XQ9iktp5h(oU#|8RS+Rup^-J~NsF!7y~G&z)+VC(s(IEmBQe!d156X|>gx+MTlcHO%x;s9n*c z9@Oc*W=|qNwhgh(_l|ZPY0arJsCD%gi`MDDiQ4LFan$M1*+4x)()`W({A z$nk!>#HvKd#4b6??5itj(e}4ziWRzgU4!Sv$B{n8tnZenqIB@zg7#;yRUX=~p)t>L z!;%$x(mp7)}R?&>irwxyAm)nNXNM~1~x_o6rKOS!p6T4)4#(;khhnv zy{EFf>sxoXzkr`K20gxU_cVBGV`nd-`rl{2N;PH;DLmz$Ro2dX0fy;t~@76LsA!-W>x-l`wGD9`O1d zhU~(+TLF9kVE?1xVBX>2VqS4@@o@iYc=&jKYxwvC1cU?x_(Vka?hz3Y|7*j-!NI}9 z#UsMUCnC8|bf1Kb6w}Da{`NNY8H-BrmcsSVjSO5Y-qI>tTFk<8U^S77}FjC|H?Mre1Hby9HTx@&-9Lx*0 z7Zx@S1ug)OjZ#EO5C4G;yT^Mf(c~fm>c*!WU-YMbiqY7fa(afIJyI4oNGWcz^ZF{G z!kt>uEcwvzwfDE_O+v0PqI&NhE$m)OtD89aM`cxZ3@`q=;*rrX1%acpt2#%P_E5aCnr6-c zF*(&;qs#l(n2uv(q{PDvBt9-74vs6PKNL8)e@Tp|hmjcH<9)JdQR6Aqm#Lo|PpS27 zJ6I48S;_e~C!}00RD?V!Ek)c@K>iYZ{Gh>jy0VZ#tb3tWd z5BrVN^kJXOhf6v&v`N=|VU z+jfdcN??k%hD<80s{A`r&L&N3J?`}d>f`E=SBzY&=TAOHvK!*%6^Gvk-TP1h;Ly|b zE?+Sqh-ChW&=?a#tHGl=)6PeBn73x+>Ti7IY<@BgZ)Jkbv7fo}>fn+O@xQ6BWmoRX zi3xq|cj!q#Om>=>qT03V2i&`&CsqzUO>~V7p>dA?=!&qgY%)niC=q^y=MBD@gMbxOyNC=Gz zymkVXqkG{uKz)$8-a{G?xa?X=<4rilHW!_W()(opvd@~G3wGlL=CO$y3~8QkhfNwO zc$0Und?pe(Mk*A8{MFA$uq73PC&$RdQ8N<-S;l5u&AWF1kqvOJ)wFH5$pyon$_!b< zs35oUBP^bShi_%ES9BlKErR5DX~o8*xnrJS%ig0x()Ueeya}OxL#Eg>O}yN-@DJTq zCV8kV+07qy%RTES> zF$)Z;O8V+s_xr^0V?amSM&b4YWTf#s!*&|jLTmWIlwPaniUQ^W*2e=PYMW%7}cu_dOgXpOqbh8&$UD7uz#h?{fdE9a> z4LVbk|I#t`7V_j^R+Vl5xudJMtZf172r!--lpxb8#D3^RE0&0VE+ z9D<*9Ic;^?h8l$sYb(ju_UTr6bQ8azibO=N?FvcwnHIJE+I!|CDF{!3G#>ZVFBS!Zkm;1s?;Yd|!Y1V&lxW-3eMG@%U&fVL-u{ zVuU9{LqV7Q=|nx-Yui$6&E&MWO-D|VeEy_pc{yY~tD>B%U$>P;6u|xySKSp4>Il`0 zN<~5IU1W{n+_}(!1!nz@u(4ZfBqtG5Z%)uFztM5>lW>@D!e4c$ah6dPOf>k zekja{Z-|vhgacZ?O}^inS1PROe_I%sxQNh)t!GLK+C;O)K%40etA#>CwE>I9vb826 zn|*}u9mWCtmjzNE^Gzo@q9sPhTQge!#R?lRaXc@uh_uRl(bY^awv4H9`8HKut%15I z@*@Q`Za{qs;)M#1rjI>=-g0nbqB7x&j{b61r$p`b-8J(Bw;{Eq=~?yuRdpJEFD30= zEuk@&#IZzqln*DcqTBgQ9-)QcZEnKxIev0qj7m7|~5HE+er0aqb{>L9J->DDL zBn8wLf!nFY0TALv``Oce<-)z|$(JVHA3bFxn_+i={)EI3bSlld2Koo0yq+21JLUdH zf=5W8$W&0D!Sq#6m++vk{wGR4t3Pn85gyI4<^<`l;w($?c`(1WjP_*1XMXpz$z2oa zsDvB7d$#qf{&zVoJ&8y)GY?h+eM`E@Hh1G&Enu4TPPQ-k&N zSqPd&`a?jfQd}uJkpfF}0WzHhnFGv%X34r%?7ZyW8OI+|nzMkRk&o^8JP9?t|e!zggd@3Rajh z2@#j`s|Wu?EiPOim)VzogKIk@Ejy>JK(6IIojKc_%|ld_>JbjM_lL0YuYw|H-X0^vy1JmYpcFFWr;$bf(WQ zlQjqZ7BQI30g+L~^FFCziog^B)FV;ku^)C8!A)Hyko0dHf32G?$Rb?PX1clOiFNt{=B%_b=gFB$n=aS!z~i+4_hxbOz!`hhYE84?e574WD<2%`Z-^6qaSB~%0`0~7&Dyh4(u?@mfNTY1kM zpSTvN%}WR;twr%yWH@nB^aG+lYJZt^ZU0IYB;%Xf2oZj}FF_$Z22cXTq+ecw4Ql3m z8zSt9Uu$w#?d`ykqOdPGA~y7dTiY%JR4G*c0FxyAl>)}SEyBU8Cl5P|U>G&4%rj~+ zK4Z!y_|IOt;eyIkJ^D-KKq&|oY0#|!QC*f|zcd(PP;Wb}WMOQ=pw7b1E92C3)%oA; zP6?AUAK{XCK|)mufc*fU?ENxDtqRlyr9S5iFA%mx&z?nEBc|;>?k(c&{eC-j3TzDTUPw`YY6U< z-CH;0Jal(M7*$}>9@;K@vAUe!W1~keo=QK$U-~9AjXOm9sYNH}R)qAq34Q@}l!`9y z5^x?^Xb>c|T#LjxTNv(0T?4WuW814Jfq<`t{0onl7@G`X3#0{US2GCIZKp#Yf9#B|>Z05mD~O zv6XoAGCRC-PK~Jl#o34=xe^l|dU(fpgzKd}#RV3m<|r6ih+-JCGC>Y(q#kkR42_2P zp`q=vWLXY9bT`0)N2)t8g+8R|;t zNFS_{5pkErFSBLF_&bh8k%w>`f4UGteS?Uu4ef5A27C3FihH`J(O>*_v^^gm^{TZ7 z+l}o>po^dRIcLliw&KQTh(7M|lHN{4d{n;!@Pu;xfe{xIe3dJhodk${i1eNuh8D@M zwEv6E{U;Uqp8>*y5E-cA9RRb0*@IezvgI#pT3$6PS2)dUa`*Oh7>W|wCKO^nz3??+ zTC~qP9b>DE6)^SsM!uO`h{jy=u>f=IBTsheGF862zeY&y90XYP#ez5j+9~;XUUzjB z(`|t`NDI|yH~mEmVl$9BOQ-$PO~^mYfd%;Frl#2;-ybOx3{ z;+!WZ;Y454_S;_!wc0>0NNY-oX0V|F}x9$zp2YWInTR7eOVH{ zzQ3A&$B%|u2TpmD@jC~sSI}hdBnqxN3$N~Z1luluQBb0E*1KlhPN}ReS1&Q(jH7y3 zBg{}wqY?GgAQO|4x%Tx^0e9=-LQ@0nhpnFcqg&dAS{kN`gh zSY_60)tVi=K@2~&93%GqPFY=DDafG<&VdUuc|^49(BG`94{v;Y&Gzj!?F?e4>ggE! z7-x>zD$qpH{OB~;&fV>LA^#2_E3W;<)B+WT^h4ZU!mJD3970JX+=B*o@a830>YoX) zHw7};skgSqjq#>%#wa(1AXBo*52HSN;FQny`*5l}-)!92tEuT`Z(BaQ73O>#t$bWX z)`RX@BG?{E=@~~gpz`hj(mUlNa0TNr`t{CY=bTuVugg3XHt}`n9eX}=ixKg5;k*#J z6-3e(yT_Kn-y5b7l};pJ`SZBD}m{eC-5 zKYWjK^_Zv}W2}1zm|xxham)4q=7*MF4f!6S6r^XX91b1bc%Iwv(jf1@{N?*O7foz-B?6|GtEZY{Z3ZS9J-zVtejmug@j(bnc_ zl(E}$xdy>bUAa0G9SkhbR=6{s(G=V=*6 zYD{M!_SN&-Ddrrz(`^!@sY~_WfuWT|zjU6fl!SKa{(qc8hIN7LjxSnz60cuotK=;?%uxTzV&=B zu+^b6R&`ACgi*~M?n-2DWu7$R;fICm&xEiZ4e&zW0kUiZS@dQ69es!jrAN*TTkC$u2fo-iJE|O3zZOoInYjbVaW7pj<`2z5q*zw2Q>yL&yR?{t)is1K zaRdsBQjn+#pDORf&t>`<;hcKtdA2NTfc9ib^zhhSlKpb~f?yTmWcP3*8Iot_)ng3I z+{n^xqS3cU9Hw14Y2ek7Qz&miCs`(c?4_Y2_X(MDtK?6I;1E-#A(R>lDs*Y3fi$fd z44Xq7eYq;HjEDI3&n>Al_^c2v*aCM#JZ_384_7}!yb#GZtYwL)KvZ#U^er(GD5aWA z9aK@<_&9!G)gyi%YcctgjL@VV29qaV8(fc3EGWSM-+S7=m8^!-2q!ws-(_nxWkKk<0t zmd4NZn5$eM>>A=h#XYmGf+aMEdz_-mu5T%l$M4a{xaX{?b~6jeUjU+2Daj?KRZbTs z9VSEuS;5J6t1N~nzfr4~hzg7v*<}dY+JW$|a5BH?nLiX%+BXGfDtlQJx zlb~hboD7{?OA%x)?)<}VPQ#f$J6YZxp)IdYxgJ--s^aAC7#y7*gL!o43xh9%;K5+| zsFU0N6)TK)oMo+sF=FN4TLoy0r(1MHQDMd@F7__Nwtblf(?N6WL>Z4FGzmFA;1$_Z zQmu%0G@t$Ub99WpJq}{(SAF}VN!AkzCe;gf9Om1P`a`sG6r7H-!KlvET_7w`(aHsw z)zwx~Ivn)A{MpV45Tv?kuAq(I>QS?}dgJ!M`RsYbD+NM9oM)8m5B5G0K$rk=7yeN< z^B_7;#vN6o2X-K}TEFJ;21cR?QD0$};=bLzJHQV2j!-7_v3%He0~_e!L;7uIl^JV| zsf!yuffZfJI=0l<9*U=7pNiSzBbJ&N?lI4Ys! zaF`m?L)6+ZzQ`D`flSPQox@I*YF7_-@Wl-^q420Sdl?bt)_wG;&Wg?x|JB(Ej0H7f zX^f~wK5auTY;)(gnDh))4V8j2%Uzi_xjH+N)ZWz2w>Q5(p#MG}t0_UG>zr0XH;9|S zV@Z0wd)W|2xrV88+^j#>sv`=b0V3lexjEq*X=Molo=jp|&3!2}Ia*Okv?)hcJx8zg z0avE#(l!QN^6@OeIG5xhd|S`NIx(}Ua;jx1hr}Hrhy13R$2fQ(l)Re_#x_jmd??BT zNGSY%K}`oFZiuHoz`zuDlwl2H=DIa{c&a~H{=5$%*lQHSY0BwKGvEB3w}bQdm!Ddl zK~9&=3UareLWts9ztBljBp`za*VA~E8AMpCg;yJ9yGNP`{^kWVQz3=}MlsJEMaztBbr50mp-mk6pN^1C&8E)ZmV#|jS!vHg95nT8> z<97fdGli$w4td|P)y?ScdEl4cdyq(UY$bi!WGQy*>4MOC+1lAL4VCSIdbz&NFPn|6 z%<9)WbAaC#Y6_4a`>t>ZX+n1A$mhLsCb3T0ztR)m5zGq z+NcHg*16XEV>RiZIoHE_q4M}8)!Q5uDlK-N;VAChL|FpIje?{CWTe$gbYJI8&JYYSnXC;d?zKFi)gI$#f-|Ur<0jn@*6Ij4PQ>i!AC*4m~PqE zPQvX1%lDYUh@HN4IFnK#=y<#@8qOC_v#G?ZHYy^NQIhg=k>{$yz{t!|jFC&$ZEE@} zNAd{Pq{o*mNV6!jg#i8ggKvs^dY9yO*98hF?va4}_U%bFu(e?;joD=?R9wEZ!X-f7 zuU$0|^UgJ)5}3EuNcGXm4P@pG8(SE8f^~|CNI1hmzKluXfVR zyoCg_l69Z8;QTGl>4M- zhFjSA#j;Ve`SWQlcULFZP2T9eC&UQ*kMJA35aaQEZ zSNYjc^32uN_>`#o-XL&HMoyERp|Z?NrAN18OhskFEGFxUw^># z`Dyo&L^)s%x`|)nq5I6O1)pOTXTiGcy{NKRepP@P_NZ#&y8Eq#+qA6>!$};8S+0bLxw6tOrU8eJ#}_mF+%B| zC@(NiPIM)dz(;z{JOaV?57gZ2CpbvJ&W}jGyuZ*LNQHkZZulA;-uKZvr3=ol(K}G81U-pZBZxxKr?A?~W_|}ry z{r=#S#L_+NYzIT4Zj@mUm1+poD(Onj#|rjtLM~@AF3H!v;LWwvDD=Wy1bT*@>l1MJ za8}7(@>aRHDIVt%ygeya2~W^m;{5k}{}+%%b=v8G7x6rDuvtk~+)HJ%diZNxsUI$5 zTrnrH`X}8d?6Ghm)^VYoNVru43LMNqav%0WFsNHR(#_Rc&1-FzHtW)d?yIkS;%ncy za|2*^{^{j8>V_Lepj^VOQ6;T2BQW&q#_Dp`biMoX?@r@9w<=ndvik z=$%mzRqlF6+*l`h9nBZ5QH(n9IyX_g4LS_?hsen4NCVfNJbajTPgnzf;_DLxnBN(zD^%D=~QIIQS}{Ck&wsYi~QK4lzf4$ZCc1X|ONx<*l!o#l`4YYsVX2zNA`o zlsc^M^4R(gU-lnq*uM;t1yigZ1oFu|422kmoGe``hE0sD{x{4Pj4u^+3kE;6bRY9T z#cC1foTM$Tn~yP1OLVZ60pj;RDkmmaSnLGX9L`kE#4X+ddImb`eHM0Lfjw)+E}(?x zK_1s7&~InmlISjEkd-f@Jg*MB_%d7k{npA7Cbzxu6>r(sKwu5%iroSPOK-IT*!h~fkrQ?`FN2GZI5cZP#tDm&iC2c z?SG|vmpYxP6<5WI)88J_?J$I5k@80eF&QI{N%w*x4>aZfqI%1=PsYa$Mwf#^)aQco z;BtY-^bTE@84KhMLeUhX*KU054cJsuz0oqmfi{Qh;5~>K*1^F3;>ov#or@r{!1v4a zhqCX8`PG@)g70H6<^(vz9Q^b*3C=`_DN>=WnYvcg(#q6qS<6vO8Zbg61>z=EsxidX z&xH?t^3-V+_m~6_?FbA`Gu{DA5Nt~}M{!&naZ?A4`kA*O+!&2^d0(}@4|KJVD(Zw# zr z-m7$~_6kNfQLIx5b^Gx)%}ntQ8@@|R0uV+QYu6SZ;LSG zmK5SB0~}a6Jr3^LenA{|r8AN=YYXgG1l=_3?rx_a>d3R?+!~P&4b7%lzFelZdeVdt zm7Olq*!ae3!v+(hV+YeHRfIT)m^dRDT)B}fqt|&~zdagL0@a#6-=x(mO?lb~8;W6X z{wp#a@Y=MAfkhPMWndI6Wj*7A3u&5Pcsok=BAoUr&PeW{W0lbe>9;Ex9lX=)_zb;( z*!Sq2wohR4l-T2R{Gk@$YtO~?oA2jGwU%qsJul^!w>NsMS};%CKewqTq=_wOT2xz= zks_04zZDLi%pV2~m4KGvIk#o`W%tIZ1L}NVJBLhv;td}3S=Kg`FtN*Ec^-Z{8OiMt z$?y63g?x;Awm`x^v-JOI{^;LW+!@}krlyFOxT49rO8bPLpVjO@1x3(h=*1pHPyfJ< zj!b&0hVLH=^}}EaYlKCM+F}jk4{tRTL+hgoIoq*w6mtQG2kN0x82Y}UM?rBARBa!n zST=F9(UFA3`JJ?aI!F(*W>_#s;tp_By7hzyrK#RCgvzvI)VQ#v(YjB!V_)m{qKV+* zC6_3!5l5kC&pVkeODbgk&-EWJ5?AM2UXGntMY}o*s2U`hc^8u9qXgKe&JERRWj)sD zDXB~KrW)hY)M3AG_Y81V%%R0ok3xq-Gk8k4O0J5H zMFr;DgG#X9f^J_fg8SA~@*NN{Ewamxukyul=Ea$3)BJ;;IHvl_C{FlppX;yS2mf3p zx(-=+e{!CN^v4jEsg>Zb$G?WmT{$$v>wWT`Cq_J;((@!G6<^(zu8QljyHO)-t9kUaH_yPSWQF?r){2XXkS}EhTR{=qvHCr+IVw z+H+E@(lbU!$$w)Lm7#iIve-qtKDbu$N?FzRDd8gxs)`t%Yl4U;KL^46L1C{ZlRVS< z>{(ppe``^iT4=vcA{DM{NhDMn$%)-dFF$;-E@L`v1N^M09cKO!!r1pFbv;3>L!DKUKW8DHt=3)F6GNI6Ol#7tUn@g zzSf}EhjlN1451J#Ms=EJnL^T&X}9W^$I8r7E7)IyC^uQKzgyNmZyy(^D{I=)a{ z^{Z1qNl$=%5%B1t7c9z+EnZd`XD>(mJkgZ9BbDC$S{8VrE6(T8KX| zMZ_<|t_^XCyGe$cEI^I;XJt#A2u_q25d1Q-43~W%$Gj2!yHv;STWMsy+T*?O>HGiY`TE?FZ@q>&9gQg zBi7?VuKil9M6kow?PvHe139EJ$3OY5V{DNeX4K7vP^gNX?j%fF6javCKi6?ukYH-! z_QBO_GJ9tNB_v5$oA*!^ipCK`Yy#=fk=?kfPU~LNzn+v$Xr zU6eC^4oN%&R;8OlCNRC9khF}MglpSrUxg-n6+08u&)vX8kCJ4Gx32DsEX#VKZ8FUv z6ONDxv9+f&74Z04y^7`QfrJvbH6kE!Tct0~x0U)Qd!7j%K&~&fU%}6V=87>e8Dk7T z+N8@QPH1DZDd~wf5aG_Au^U>)x@EJBZ6DjCJ_hft6`*%8CNBIBZVP%J5qGRROzk5b zaL+Kf9{TV_ukYe^5RacIUD5hz9Z(+1EmR`99O8iT^q;MCw0wFG`(l&VyqA=W)N8R=kTdKPx6d;+0(hYkF7R%&+D{}7B{Q# zK>Le}3tCEKprAiu$Q*;mi53dV=ZR5&p7``um7O)3T$gm*@X4p6s*2WbEea%2B`?FC zTMPBSLOxoBr)97{{_=!>T$r`G@=?~A?u(_=!%Gk*Spa0maS>m3!W1IEB2HgaK$r}d z6#9!;BSTFn_)Vm2fW;7B+=AM7o>4x7)MuVIoGceTC6ze0!7hCVmf?6?t&-Q4*mPBG zD&r@+26;o6N^G8gdoqtc;B4f);Hr?Cii#>4f$wl|yj~J`opflVfY?ZLM{m@8v2m<6 zHEkfkABCTqXo=V9JRcBKdP_pM_LR~~Y2~Ie5cn`g%$jD!*EAQEf-44@b@UbvWgOHqic47{K0IgxlePBE|N3J`#SzOm zsLt>}oGhzQMWpI2|3ot0QM|qcd`AIES8m%Md$M zZaVJs`3{g_`|_T=7P)BW&IiR}g5G9kx@`&C)MK*7mdQ~a8Pi)!t!ET?r zU@8|m@o%UIgbNRtj?t}DP$5CbW~5GT&jG5g!9?A*b4FZ1R^i?k2W7PckkC>EFJZ;w z>k9_Q(!C4QR{yQchlC&Av92vD!p}&!6g|@>lYX+e{c=BRM{la#nvzN00e)&i_VX=& zIz#gnwYEUO*`3?$jV*Uneq(YJXDtQ$o_B!f zi%87v6`nyjgH{PVdQf7BgJId$gkCty@P?>V4ph*`hNB!lK3wP&ihdKxFVkO9sYnmY3Q3r=t)hung<71WoMVs$LRawi^@3Cqz* zd!v0cTG^3OK0VD!z3s7@B#GT!P-vJW#-eCq!&sZIG%{m5l7(a?bv(ON{DKKpKEJiy zm&Jtifbd5d)$a9WNU}7L6NhMPe5tRWivSazo@pm}+)6%G`Rg-gcZ0%0XCu{9L_6}ySQE%V{7E@ihg z4|`*K8-<6i8lJ&|uQ;7*Dyb8t=jdv@TM!+9w&)W5{@C ze!hs5A6jN{l#^=Vw2xtC!~|=Z-YdS{4&M5Ze+iEKgwT|dA#KKICHA7>wBjx^Zu*CU3jAGcjrTWEcL33|-)!_tY6j?je zqM}KLrk^z0c3%83QENn8eH7hUC*AO9NQKEaV&s%SIZBprrJ`I>d_{ZoAIQb;0Oj)Y ziEx+dD#oX|*#ntuW@yQiwOvQlpu%d@$~<_*wI%h+P4IwC{D&_Id5*qG>Q386Y_i`v9{GSJI?EpqFT7n0 z3Y!#X^1TC$b*&d*6ydX@51aO!Inp;RcC(TCO21`vK)xXYAvpm-B{L#c$D8tBR;4FB z(A(b+eQx+v(K85yXX8A3f&z#pJ;BUFEx-?#wqR8#0etysttj(ZfzWGbod!BCX1i>h z;TsPGcjqHyeLw)y-%{M-W{w4pgjhSeXEx^qN}R{-#K!2=Znw4TqR!2cd5~Y?#hgu}R3-Tlf0>H(J&r zk7$H-;^nWPh0k?{F!Auf{!!7Nt8cDFOf8M3!b;u^?>iI9g%VEkv4*MTK;?m=J<0Hb zN2r8taLVUrr0twt5wW%A>g|&B@h$bHZv4l^0*u2hbJ}XEfTIFaUq8Yxglbo|cs^8o zzTi)j6jh`_-H9DNNHMd#e^1=2whkmM;m_F6?@5@)yHMiCw|&rK*?n}>jJM6_j=U(&9wA>(62$sBnk#C?bx%cs0J$(2v=p!dJlw4 zN6Po}kIRT_wZ)l`KgY!qxtQ8?xY3#{S@`Qp>bfT+jq=Z=ZIWU~@laBZ`Iz+HOfvJ6 zD-N+oga5XJ;33A;iBIw_^Di`&Sgv}~&^+qMz890Cj$19{^)wJ*^3DUfkI%NQ!*=y+ z8`Lrl3oMo?7!pOgk8F%U#xaBj6y}6(++pzR%Ydup+yP9xUd9aRv?kV!?z4nGW(Dw_ z31ip(*%Nd4d7-|VxV3#QE$lIC%gb?wM1z4uBhf$G`w~@?63{;pPKeB0?v!aoS;@}P%jdj`c>It+@}pCcMF@{Y$zsClt-*IJ zu|KOJ*?tA^u}zsffI79%;|UCbQWh}ST;b&FX|*rKgX>f~RU%rWuBS!)LdEdAy$tdj zv45#~%Qbj6lbGNTV`PQoEy07AFJ}bmZ9gH7@=CN^ed|OXQoga%pHhKKaTSV@-ZS=^ zk*Ra*GYeC8y7c?A-mJ9rX@-=e=g*&B7|(W-$s;2E$JZfQZ1k1(rcRuUg$Yis*{{<= zt~(U8H09Vox}Yc#v=7t1Dyy$VW8A#PgL@Bqve1gNGp?CLj8-1KiJuPxH~khl<-^89 zEP4_7&?+aX&)IM6*?Fpz__cdHg_?N?R?2;E5|^|7=xC6rD(W*NY|R64uD=g?In@7+ znbK<2Hv6X9obpGn!#vRc8?*Lmbw=TzrrM>V2zh;RhEJf~d<$V3D=!S7nozxU-oq5z zyM4C6*@BoE7t9lUU-@-GlFR8`$`isGl>rN8XJZHxax&1R**mW$HIYl0%zxSX!NQii zUTov(5DRg;!in@OL=^o8T(-9?i&`=2oaS%6|Bht*XvMttoKlNQhh3u6CqCRP9T3)U z99%iKgWn&UD?mzjPlT#!y8z}IvIPsU%B$M<+^6@s`8L40zz9z8Ie&M)rT63sb@}#h z*cvmGXN*F|L=bAZl%-0iNl}c~mot&R^KT0H@2*v~)I)MJC4uqT5qEcNL=Kpimp5TM zFG5wHg2oq1Bsv*z|B=~GA^szbY)5?hGc7l&&tgVz5u=;ybewNBSwVV!ugK^xj{ zH}&tcVCjo@HotY#9_~idhsaV;Q(WCn-&R8~!3kEN5XQx4LMMZ^C)xLg6O0%v7q;VH zp6KTBsijA%=#TFeikqdL$;q`<>x)WS!dTfKD?r&t{#TnMsgVVF=n7O|p%toRBH*YZ zvqcVX#{&Xpeb!*F>*rwi3CHv8AeU)y2s z)4Iu&PAT6k@`)XA2hT2FtAXX0OS@ea1L%T5tAjGwn#b^_|6TqYDNICSyp>7F5W{>G ziu|HiC>tM7FAa@2HuqnuR=NZDR9RxOfR3g+yMGrfH-;%H;HRy>Nr`){c1lDJoME^k zK~1v=poS)8jnj^@w0XxWJM`Q^XXN*VpIB5n>$g@ItjLi#bjf;H?5tg{MMO4NR7s60 z=Ka$X+voJ|AlX+*=krGgQK2TCeU}p4Td{{G4nPN@owA=S~K*UfEUSJUvmtJtShR6n#5r?=$rQ zp~|=(jq=zTIWEwduN62EI^O2A9Po30lQDm6w0V)?D5Yt&wm-t4l4vG_i)H?4Z#Vxb z4xKRT>WAt+^UGxO_|El3vpS2nq0c`9$JtN*fFF!?6=?4T2-K$w7J1yK6ZFv-A2?jq z=j7KAPoOnok5=M}i77NL_s%O=x;i(BkftNYvxrV!>B$=#J&6>?&BsV zt5nC)18=Ri4sX0RR-osX)9^24KAcU$dgDwg&(B|NH3qrJu5a{~kxVr&dG5i8yz2mFtgCXy?)P7NgRp}EVM;`%q4K+9=t6j(jNDXy{7|6BjC zrE}4*4+wjL@)_T@T!XaD0Yx6QEWkB5Shbq_?GsK)8S{aCIVr__Mlgr+y5jg@MQ7vN zfB1kkjYcVIjFoojH0t9-s(?_X%Ec=RJxs_roWe#VIr@`R-MMa~;|?Dk@oK4q*Le7S zqv-W8-iTZ(l0jA)bWYC_o~BA-AR)3npTDQd*)B1DzV0z|UM1_b<^{GXp4yA*)*9V& ztSsZI*|?Cb6QOR{ZGByiCEM73#?&8ljHEFIu6~3QNzIquH0>* zv9(A1Zv?0miz++tk8igV*DWkY=CTvN)vN!|F&9LMX6xj1Kf{hn+)Hxgy__9zUMre$;S z!a75W493zx+v=ZK8mxAI583v@CytN)tc0@r{YYM>_r$@i*9sza?6kaSw+^U}u=?mp=ahe)~;rH)27QW^RleJKxpv#>}%$_w)lpPXh)Y##2 zEdR}?Sl#J*I)7*d>zbwC=C98+r2Q1{l^mqY{;~=a8?EpIFsdqtiuh24GUR!^m%v&oEMcCyj~D! zTG)F&!~FIwhS#Q}HL;vgl9A~WZoO#`H!e!?lU{Vg!9YY)#$-}b5hV$(;iB@dWLslD z1K))6yV;dISN6<{yCsrAF7+<<&7!*C6vWtdV9Mh@Ha#Q9M;XyfmqY)`qj_YgY+qXa|b(Yv9+X8Ps#U5 zOs^yz9S>PFtyZ*u$RjDR|HPD;L2+kpc<7FGI&oECejvfoMtaa$-(-!q(zUY`W~v zspR!L62+F4f#lqQ!rmB$QB++qdqat=#Dc7;LLrwi!`dX_*upp|O2_%om;CG28R# zQee2M{ey(jM!<*e{h5D4Vu5Y>;IEbMjK(x$g7Yn7OfJ(*P28vc>C7;din-mn@0KIP zl!-EuQvpapwOA`iJaqNnTIBZ+#@<%mD=3}S19fFr9?rxkXJO1#-`V%tq~Wwx2Am5I z5S61`V24z=zmn3<4t?Lyae@ca-;x_61f9bx4O_UaAt19EY^xGeGSdKhpEziopc;>6uFhn@QzhpUJrW2S$3u zX{EWdk7OGgE9$jyy3=9Rf&r&h|JQZX^}m8_`8%z0laew1gh)ma1TFC8p|)T~lD(KS zAjXYjIT6k@GvdZahZNoQFLV8oF4w&!G<5&gyv;LzK=Xd(wVGXE#X7PNesFKn8EB~s z{*jL3m~H?uNC*p{!Bh|jywak8RCt}3*|MrwrF>0*Tz|V9p^>*>$E@G^t=J9~f~+hn zImsKC)z)!X0O{0=9L@>s$3nvt@#YvNlO!RUmi97w(K?$%I6p;;EHL(d_5wA-$mG`5 zxb4R&2cuGSCVuE?>0L9V0`Ze$U?%*6G_@x40Pdb%pSll_Y!4%>wqRYo^bBIbma1zp zApXqKHUKq5f_^G8@(>S9laOLo*KH_az7;wLI4@!<)ZaU|du28$Q5M}k31&;4%r~~SDtKeHG${i8KTC*ziIWCF z#Ki$Yf7-Sqtz_9$2Ybb5?eNGvUn{T1fM{9S{>JV{b z-nLJlN*}cxTaMa&Ed9AWe5;f@K!vpr<8Bid_ zw!xW=c*;=tqL5&$xRT65rF`$V+Q>f`Lct=fK&X@e2TSzv-A&PPc~XfS^gXkscc+VN zNjz;FhKBc$dEVn^L{w%EvQDJ|jK+kM4u+IZRv~p|Uu{dhXS{DcE=4`o$bvNr5NGCs zg#5u%OhM*9yL=9>;0v2IC2vUl;@l3+piEN$A4)S%2jlQ~9pitGqQPtI2bBitzj1i;)czgZZ`%RfORp-?^|9 zP%Evxx4$dxAluNg)5qQD;X&jmkC$6}h>kLrkS#|Dp%!a1Zk{gu9}+B_;9&c5<8|{b zRfe`UIfSyT(6jFZV^SgGaH~YIEVX3YIMU`(MaD7T@csfb>)GqLxM^l^qAN#zE|VR7 zib0R7)=L4lGJ$XOqbJ{AqzkY3p09}cYf958KYKDh{CIyLO{iab8sNKoKdqNEipIQ! z9whpo>k*9BQhuroG6yFqL<0FuRX*_?^p;D?O>W0}ra_dMQ<5YKtKyS2e=|&p%AU3g zftFz-T+uj|6GnAOX2Gja9BU=)PY^ce8@@!e6P0e0{Wl5Fm*K6cx#ngAtF5iT8|%Ny z26|fEPiq$>D=L#~?#fZpX-;Om$eubH*YFTGtk zx^NFwi)xNn<78G=Yr@wfqj%{cf`3Y$EFi~q+e>r7;iAqyx=C%s548G4&V@b-zIx{a z-PCU>xN<39wa!b-z44XL+*h@l^;#X8GE}i>$s&GZ!K|#^SfuY`qf+nN=s}kFDcYhv zDSf$TWEX?UG5|%@fDdd@1!{YXcWR?_+Ne|nThS{Azwp(TU(zYnn(Y&l+Z4r>bbT-O z?(yOMcK42}rdS0ppHV(ax}jam8iN`E7C60cu7`Sv*JKHL-h>-m)@s9TymvxFYX@7X zd{{eoUklJc1Tq9%y9<(+14vN+(%-o#s0sZ9P{Qc2gZMGMwX@^P0r-u+F3pPwiiOXd z_?9V*U)d6jsQj0j@3x>f()dP?)yxGa%FwIszNym&@@A_$;G3;`db*9HMV-;E#L}bH)5pnLoc+-!iQ?XcClxhcA~ak##= zz(&uyNO7amPI>o|_Xo%OG48&M>L0zNS4H|y^odC1suM#Do%EeUO^!vYY|(z8GzYNX zUG11;Q<1hAjq|5(>2)^_ObkBIPq9jV%wSXn)P8agLUCA@@(#N!vFe=4Xo7nmnUV*^48(DxC-n zDxzjy1_FJ~ys0$UDCz^c2w_3fy@$bwXmdnFA6he!TY&&M+*Pk1(xwQ?W^+!C{*2`5f-3z@%e(_!@j|Z0l>j#!NuOo)i`B zE2tkSBbSYSYXzTk0R4j9*-H1*Bc$jRlyZX82<|30`Lcm^dOKWRgcLC>FODyk{GmAkjq&4 zq{0~8u5-#|Z8*q4WX;Ot7Bg4pp!MfxPRF z2GhBHn6HOShRnO^5io$rYft*AEygan65xDm|J(PXfGw5lL*`b`?G?*ANcK|A)$!*m zCBu^jw3(T|Cktu5f6^d`+%@a?)mo!xL&#CvB9L_cJH`Rt$&69?ocYUqJbGnVH2Eqs zq}dKY34k#JU;+W#$R^f`eIWa0M+Shmo|2=j9Y4coh70Gtmmue8TOo`@8(@`%ao}?& z4JE#|hOHw&=gR_D+si(W6@w6EbVL?cM#`A2M2Wvp8Hk=Img znk%@vdDwCd5Ce#D#sAVtew$G#18N{lS3$XAmy~;%G0CgQg3sPkSz+8Qil1W`*?b_G zg?Z#EJS7i1k(}BZ;xAI>#0^_zJ{+zF4hoiflm7%WrZ9L=#lGWs;eZn}WcI$~s3Uu@ zaoN5p(B`tpCYE?1+)?)z-GD1ySU|p{dluUJ4Hi(M@h!EJ!qbE&mQ}3T-!>GkId&Aw zfBW`Jm`56^h8OPm2?L_$yGuYUUBe#4v~8XC$fBb8D!hmuj|J-Z>|?-rbYCv&sLHF zjr)agMI!ffLZh(GQXIER}+-doI8`lAsy*2LoY;N8-gf$gZlTdC$qpfg7y)n zx#$`oBIcED578DsA=)eJ?btp&)VC!sDc~e%{%#Vr+Fnt&MqM+h35x@A zH%Zh8ih)ANzH)|=dcW>CwO@QscX=xzy*c7r!n=Fh3zbkx|2(8cjV#uo*$^C$j1*!LKWc)LT7#zSgjb%2ONuADCoTr;LQgSodtatD zm84RT?sx8+0!$8o;@}efrJfB~u+-3g_Xz=TN+Mxn&@VvEeTe&f{c-2$SNK=V;z3x!g$QVj z0c7MyA@fy(z^OtI_UoLo)0xVC3YsD%S3`+C@1u*qU3In&P~2za%2UWYaL`iwdwhdG zL#|K#K7Ws+QPHuhX2;S{S@xMq#=v?B6y|tMEjeCK`tCo21obJMw>#R&KPxt_)VPzU zp!nTs>{JQE=R)UPR^&aGi=E^N!ve0s<(#_A{tL}FQ3;P9AFb=-nP-KblQ`>?@is`$ z{?M$>%jz~PL@s8ZDb@th1i!lLd4$=P&Aiwh`$PL^3%&3MqPCS#zhP*u5ypm^B+Tkr z%vip=apm1dhRT!mCk4SCR@xHq8Jwxpj`KE8<%gOS5$uK8l7cE z>QIm=F`apiTEg^8I9;u4i|^2pyet`H&BraadCS3$1MGep$;XFQAqh}ISyN#2+{apX zlSgq05^g`92{ZAyddYp)desrwq=vXfv`m|4N_1qQhW3Jm%}qc@k0w15ftyh!cU2Xp zJvQQtVEMtG@*X?NOC3VuZgTw{{d$-O8kJqb(X)zO@Du@hgnN&co`{_w%MJ*a z%_oCET{F%M#!_!cckEnBQpVm@u*-bJ3c!UneiFA~5Km7~bc@8cP4_lvb5 zQ3J3*E%Og8ZcS}5f$#j)yhxRKcB^npye&k%Su!7zdo?o@@SizP`;VNwd(T>W(TeWj zp=k2Qn{yB~bFc>F9>5hjt2`FfP%{-^eQ}Dj>TPMpDXDzY{^|I-aW3JOtt6-T7f{c8 z`DLvQ;Y2x)S^?j9)k@*Fm|LW{`qD^y$s*3d>Hadw5&tD_6EdxWu%p<)LDKNJ?jH=x z*LG*QO1aiILG4-I;U)!seN(`J%&O0Clh;c&ii zIb&8K{{8WiYLe)l`w7Nb+TLXGxQin5ZL$gf(e+;i8D&C700?3dWTad!<|?%Oo@m{& z&sVvSK?hPNaWxtbdhNcAd|Xrl*bNj=jMD##Ns@sJE!_2$)|ymQRF7_X**F1`XVo(9 z8&>2?h|L}H_l8T;ewjik**Q-1k;t|R%wAUDhhu3y4xVHaiE3$ zeo&{2Yvy_Ne&Zvr&(KnFaQZd>0nX@SyKXTuSo4=ZDuz*>(bu^&bothXH!yRsQc{mOXtJ{uza*W5tu?OD2zp!R?FxlNRTjjXo$BTZcFxa8+nW%pEBH!J&_t&92)>G_ZBUHzXz{6z!iww!HEh8TEnXR(Uj#xe9RL)IZ-yGHyq3`5> zwQa21Q;p*gHS}F;gZ^Db@=sx2i-lXi`uO~{Pu$Vg9PCb96ZAf8ll*q# zC6UTB@T^1k4(Et>PNkHX28{iHa|9@qEMjDs#MHu}ajm zmt~s{=ueiGme^9&xlLJb%wVEYJF?7#Bbm=~@>e<-zK{y-~BJ1lV%yHXQdYsVOT@dlmdVJ!P# zNhWI+C^yR__48|uTY@Dw?fR9TJ_95Gn@Cv}?XVF;HN(-;=#d(elSHpIK6a3%#eBug zYp>@eUS`1tzVSmPVA6AAyC*cVl>yDK;WEo9_W3!aL#hlY`p@>#-f*+9ihNc^&J;^No%JzEoc4gyR!dE@2fb|4wJ#*|&`t zb95TGI3Y~Q*u^D-AJw*#CJUxEY!R=|Jxv7{W+ao$*fjQ}0^i3l&3AegUFBFb1^-wo z(%+%1Y0?Wy^SLH4RP9AesvXySs#s)dV@o0LFdW?1U;Q3?wf7el5zSgKK$#eD-Tug^l*tJhD@Y8D? z25(Eka|5cSPs^o>pI`6B&~4x4#&{b)n@P9a0UqHwT{SQr3$#UCr1J>fBbNfD(U!Ka zwEtju9_jh%77Ej0*o^$^lp@Bsr7*0aI+H%IO8gUabpv2QI&eIA&BgI6GeJbNZ4+i! z^Fzm|I}M0`xnUCZhD;>w^@>s!VC*C@t#7Nf2@Ax;WEGElNTGYO|DvewUO&arjqM9Y z4WK5OHHy%&A*SQz4l~~ShRTgbi(nuTLwGq!RZmx}(;pbppanZH3*52iRiS%`DO z)?gSWx;@|W>wuLPl|R}9xf*R81%EYAZ#K49pT?T%nbG3r{2s&9u^NA($YjMC^rmvU zl9-0y$1jjSWhduOYo^ti4ceucRd@*U>Psm;T%0ks2bq>Sl9J#2sZ`!c6vp60W6d++ z^GU(~SF!fyZ2MtlZLl*)RHypu@2{PPWFc4ND1aIKLhS`b7;{jPEe2r0@mTzEoBDqPKSqA3lB&L{ZLsQAGB<*fgJAiCY%) zDHid0kY@0dO^}NtJtDc!=a*2@n3TZoM20jddxv_%WvoQa#LnfDm2Z9hdbpm=bGDcI z+|e=?g*MYG^~2-xu&;(>9vA)nnYSc)26o?Z2jRXx2ey0ZUpGIZVa^C1)Kq6;x9U>m zWxodyLZ)*nGF`8}F6~s{ED5(#*D0h=3OvaVyNWUrxiHq$T3-k(quE5SIz-yq~k((s4=7aS}dsQa}?HxG?`>O8#hM=SW` zWNopdif4oHi5q39?wB!VhX?Ou-!2_vAE}vI;6E7Bji~6%o@}M;fQ3>hSId<8&yQ2{ zf0Ksj?yXRABR}xz?jHkqAzP4p>*t^3=_ry(| zw7;YUKDz#$H>`5Hs_ z+EKsXojMwCta_f-!6?Uqkuq~^Kf@dmOOHrTm(4zTbnBSh*CM%aaONGt-b<1*XqbVt zeom(@3sOT??|z8gLO4R{yx@kZ@%VECWp=|b?Qf7GU-HgvOnW(#WRj~QP@@%Qew^t= ze?SSWA303VYj0n4l&?f(U7N_#^&nU{$1rsIYP9*hkSFw1`+9?~Kk%cZi0$O)0un;|KHi<481D{INb2AG*8J*6N>Hq(q?)shGNzT-$HrYLz&X%T|ROKZ+d2X;%oW{L{`?TWY=U1wC9_r{f%DALE7Bj2i8sJU`$aO(~* zrxfzMY64v*Goi#gW*i$&_%CXh4NtMHF-6SHEQGvdzBR>1? zbJ#apasG|&Qw*A^5?x6+dOIiO@~=`#?9-*xX#x{2yFe6674r*zz5MIqEIHMlpV`A3 zuc=#@ybNfge?G_li4LXM%LV%w`PYL?ugBLNM4FysUhUXKWyuU`y>yhFPW)Me`fdwc zS>2+O6u668JAl(x6;grSl#T$O&L7k(L|m%=%dXo;W2}%?WyoAS=u?n&-5s<9?EU*e z{hgA(ci|)Ii5wAn97HE^n)oFG9Ca(_efu&W0KupC8&f%|Z|};kgF7GkeR}WEm?lPn zt}@r%s99$U1UlnTGkp%eBOj#&-%JqJG4;qq8%fXbKtyWUuV0ReB|4+g;*qkuS0v+a z>0?amnZ$r{W6SJSw^*&vnKWrfbMqHDB~tA~&ghbl7_UQ5wZHw#c>jlr_rGHtS&&Qc z)aOTYyC4fh$9`hV0WJB`1UZSlL|yLN4{LC85A>5@&$H3NwZ~k4n)-|6-Hr@ntT+Yq zj`d3+(qU4lpZ9Q4f-Gr`+<-{wY3H*fQQRlqr^eMlk61JGenni{Rgyj}1zA5nOg*WD z-gHh-8D=_ztkHMj>M^XT(cYc}BOl62p@)%Q!poA-BD;Lcj;_!<+F)SYyhTr&iD z6hVrw6G(oq70EI4U1xNB_)GFz-qHoxnkSK&Sy<@>h~!{I((Tp-AFN}4KK$%EvPMa< zA%g0V4#_}d^ExsQ`2`8CnY#iW(5JPzkNmz%?5J2zgM*pr>q!H_EPt5_4Ps8~*(7>5%Qlb?|Q7Z;L%Bsk0;BWE09SPxKp>sgHuv{Ni zz^QT>GUif2wk9h=Ctg@(7nvpVXAnHwmCVq`Mik66ns<1qjsc&xXARfF2SIygZ zi^ZD{+od!;>)stjO4P56iG94f77C_wo#C5$5FDil&Ny)uUiVAg9Hu&+==BvqsUFMX zC&oW9(0Q%-dr2}%Etb+c(booDiK7kq_(WygEQT4}RQDJDuIwd=I^0de5>xi^#Q$B~HoI8UtM@$Ng_Dm1i)J3GA2sTpx}M6ZD) z^pO3n$(i{Wx;VN|R@Syk-+a^2I7;{pv+91Bv-plLQ~7r`?Vi(`-!$GB)!)=39M*jL z=pnPR{pBm3ms4-NDm7ikF~9Zn$9h7-K8Iy%6M1Xdz0GL>UrIqF5(1%=o>!I&tTV$3UK1GgwoFf)XuQV1~ z&lEDBI7-x31ny+sx$|IgX{{N4v>Pe6Iui6Xw&W9~FbNwOU`IM%5Ek|+mNe1gUQUhu z-iZAV2J=+k3ZjJXt|1ghs?7nmc7Iy^MMp&noa6rOqOBIxF3@p56^Yuqm%jBWpN*%^gFV6?rEUS50N7LX``r*k z9y`+`3J@@Lrtzl=z3}Oj`jMgPt`3%LB=y6LwocU9l|!APgU7M!9G&I~u&hC^v%d(J zA#@Sfxvogf-`~^dcc}1-=vemZY7vYlGT5KqVSV`j9Q6r6e=Wqp#paHia`3bA2){;T zHT_#9zI4wcf;U~?vS$y*vJYR7ceJXdf(5Gf4CuoJBXDq9@88qg9#vG1jWeF~T+x%~ zDf(`I$?e2}DdhuTl&Hx)qXyJ{rMbzYtwxnB_2%K~L2gRVus9HAjU&34!kVJi>RW#;F`Q4E#7LNAQ!2fXQlP zsv2TCqh}xK>{>Ney@K3QSg?k>^`ynOXDq5nB7ShsHo0nwGwzc)9)0C+_%V=FdV}2| zZA4>yo2#_2DN=(#oLu<$NzNs27w|9Km7q}u{pSYkqJO3$x#~1L9HmzK@Kn0{ z=LidT#7or%6%y@!IYGz|UcJ{rp~ur)=a6HPiO|&(gv2YE$oD-ryx&J$ zU8)Iq_p!>!?jWM{wZpCvawn_tP03h;Q>Icu~#gx$r zOM%q;G0H6K<1JNP_3N`LKm5{V&-=DP8lc=erRiMuXl)Xh`dN+bzjQ1YY-nJrK!LNTh`?0YnZu;uGko8Tx1I>quZ z+;RUD72v-XZKhxt+qDs&mr5yIe0I|;$hd8>r>S!JSoCJyf$kVD&?VihBrrCHKBi_c z+|B;)rW&xdp9dh`$~VE4B}84vyE`uJ-P&T(y~SldiC^qHugJ?bXPfY)t0Phc(?&6t zt?qe@>_oJ(S}MuSQ^k8HfpHTMZi70v0Y6iPll~t73iWi!ydAEzFPbOW;31t?3pSZH zxbf+l9(HPdpf~(7r`6r7{9~Vr+Ro5jdU1=M=EoWBOCFn7aqQm;8n1Ya(R(Ui>#@t= z93B9SMR?gnt{uoH*Zh+lD4-Gqb*k4^Bdm$=PYQ=f52GA^#qW7;4u2d-jf)*wJ-NKm zW8!LeMBjQ5-kXN1)u|cIeC+B)u(tPjHSlju&3%{>Z_SmVu}qM4&=CTKaOrU6MRL2L z<)84Ev;4%Q^f~mo(k9(Wh<*f{BD!ss8g39N!-~kEwDRni@2gfhoCupyNmF&J5@xa% zw=n8$%gAZX6FE_cBrqG$=(VTXp-8d%Xv5IWT%yP#PBo9cbzS{cZ69hA$$!Tr8#m{t z-W9gC#vjii`8Cy6cRbHdVyBWEK9w+4q5@y*Fkc6UPLU&jIVwFe#g-dve#lI^lETwk zcE019&{nzqobRMhOLCkKnveJgBTJ}2bYx$g@vgb{E*`G#lCz^2Uz*IZ{B~Ejao?gFtYAG^0rU)sT@( zS+&v&Nr*Br5y{kW2)_Qotzidfa3TdBIxB+Nw4AzFE9oC`XY#%JP7R(P6lCE4mXKED z#*Pe1&Mameq4J01NglvT^UsnSAJf|B?Rj%w`l_SOR%jCNNAs=wrfq{y@`LL#5cwU5ymfMY8G)Qbo)iU_Y?#Of?_Dr%RT*cF zV#as{KF1iwV2anc^!eP)>)=I|$P>lpRX+R2uWa(Zj8t2e^s_A0drWqwNXqZ}3fc<# z+Km`a7!#u6y8nGS|KIY|%(RgmNa$YDSP~zt&*WXy^9o~t{9$8&k52+U-3Ow;uX4w9 zip5pdAh@RiTHY|~Yr)+(1`*q_W|9G*+jxGotOIof15VUEoAPVxKl}%S2?;vbJ!&^9|D~JtfrDQjiAk+`0T%+#90-Ke=+ka@UU1{yHqU zPX~-br*ZV8G=Pw^2*e0NdIMFrm&ba30E1GI4LZ5H9`q$P-5E43On;}oRR9Bq^k0<1 z8tjBDf$`=NPYxS*en0EIirSk_3x0bwJ+{^W4W6J?KMaytlpLr6$I?R+-U^rPpMv6x z9tgbmKNQsb(fbEOJ}Tr)P-2mLH1~F8oC5gSo=0c{aN^UVP>A%GZ{=o+krH!0b1tbO zR-pW=BV-zy5VCCj5oDf+e(u3J=2>)Bh>pyw4S)jL+9uz5b=otsUv(i%)!NP~YwP7M z_u)Nva!o!5It03xPMo7%IRYD7_0bTG7qO^yRR65yjASp;aZfEl*cxKL;v%dI_7KeO z9oiV|pefJ#2g81?;UgAC%pjrujul$UE8c;ua#A{?AN8khl<1ADl6VG(;s2GS7rGQc zhu2Is7H4nm^|gHhw*K0ZEZGb>ItI|t5oTWs+@sAGeB&pf6k0Ra&ZODccLNHty6?NA zyQ~5j^BJz{&@s0ea8d1+Z+!*RcQ&b5wQ|N0^OrqeEr;W1yVXyXK2wy-??RT-T6I-4)Mo?xgqAu^(9Yt7Vb z!^{-YzIYtR!gT#w8OBCxcF>CTo9h$DY){hx;oB4PO*_<}5gLzN)bq{ZrTT$VGqlu(XO3@is0Qw>yCEC{skA4(9c-Q-Jbf-+yfh5_c_HP?l) z)QF%w@%U~(!sE53+E>8>v$t>Cb@Q>|rhDv4>ph-gM^Y;E1yr(mQZjk%2kD0-Hi&}R&kCm>)A^Ji zt@#$wT&95sF}e1ld8Tx>eG52FQNksw=4YxAxJJE8!%#`O%(rBHxJfnqRNRl1v*1Fc zYQe6zaMq#RE!6T|J^G->T^~h|rU;LVWK`tgEyd6lB4v>f-GNRiBVU28nCyDyN`_pY zgnt35ubWH?{Ro@*0Y7G_%OxK!J}&7C@XR$5@!zxi%3BoeTZ zdc(wC_2+NWr`YCsSZrJFJj(d#5 z@?JO|`&84>dUcu6F*vn7%Ho)XdTk>(Bs5kppS>a)9&2UHWPw}VSSj=_A<^kelS{SC zV6q>FnHlKlX3orPDt)n$kHf}82IrEk@rQUc9&6~Q=bCc-UE-*pjH0CLK7YKA5XP3n63WCy+-K%0EC9-dw0_rcCY zQNQU?_tgX#hk(4T{A>$TN3NqSB-dyMJJmY_Oi9rWyEVZu#RTO-A=iEJs_Dv|Wp^Kt zGaoiA=Vlpwa8`>TWIv3lA12gOgVf6~GlajBJ(!jfWoPY- zkMTs)!=HU}YxwGzJpo;c^h7UC3y42Vvc~#_wGZ@uU%Uwy8VH>Bxb&FX^hWR<5N2MW z)hoSb7sd+>nPDD29BB|~g>+_WP6lpeJ$)^e;#e54V(vYr13(nA-~g-4AnkkB3G@4! zuA@d)dvQEQd0pDf#T;$H%q3Yv{pQ7!Ldgh;n{nahL78yaPoPK2%AfJ)xeUxW{%G)I zSpx$#P#H6*Gq=4u3ezRYtkQ`lb>}*RbN@V=9QMqOG3qWAfi-zBKl9T*3|l@3wjlqx z&<$n9$P?Z_bk^uJeKqtc9AwT_eG@E+cM}OGn@^RG9Wi_$b1b7a48`kKp1qko$JbG- z0OEqxb^YKPl+jAV_D9JiuGM}%dkwI(>1@l{tKbO}M}MHiak|##;m@V}?g2)@NzxfM zerGp|?>{MAfTSs^#Sr|;-FlUsK>mYZHuDXz(u9s9M1{Pw*6z0b(Ewiil4QFgds9AC zWzCHw@}tZ>;uV5MXM3a{d~~muc)OQP4nGLvG&lKBx@i__|;!u3KnO z#r&1x0{P4*e&(WWn&G3cRLLw0LEbco(uFBOMDfHrbvvN z3&vJaIwFt^8t2tnD~Q+wo>r@#Ucv*o1MjF7eyvIcBf=p*%;yY>0EbQH8=!KVYCZD& zr*3ECaCz%2L0@JKw5tFv zhlp81X;*srFoi|SuEt2?g^m23 zKnanceF3ejxxFQ;o%~i~Kk%)FMWM4nNZL(HEr4kCS2k(N z;gjFUhDZ0QT@_UOLixN<3f5v+y=FFBc5B-Up8Sp7ECX0<+TW~Lxdpc0Ob+qmHy$)? zhR^Bs0=1=_hᥝ+sck0qRo(~nI4F^7GHdLWI_wfGuVQ|0PHtqwUJYa{pkI&E$J zIms@5hUA$<3~p5&7X6NH{&e{0Pu35I=Do*Eo_slEs6PuXuinpIaar%IUJpV{McoK0 z<#ZoXRi#gxQip^zaFWP9YpBq=fs;p7xOBzAnU24j1|6Dn?w8UyZoG&)fE_6PxP?# zN%g5Qq?+{f6B3JR9LPb6DVDqyHOD%BprAYqY!$Qcys;jxA+&h$xzRpbzqz$pLnz?~naz1Xz)P8s#X=MsBzT&wPR-cqAo z8A;>ltu-PZm5Mz+)SeFtCf#sw-4CzWCqUg1rn8c)Zh#}Si|6?)g%z!M3)e~r8!2`f z<0ncphfkDNtnQlK&poNmmx-@-)^8u{Z(%$`6Sq3A>#gle8J?ay*kNJ2qTS{)THq?> z(G?Lr0c8-``_>Tc6?~Tg7iGVyOS%z;Pb5wWDY*02oa zN7XU-J^B{r{EmgPmc@h49H?1hKP)m`2!Y-0 z3sEUOd^JV|03_%3 zqdMn>otdV|-H;V(OTsKA=0J}>4wzzq*TzcZg?O~&!gb;_$qR235Z-9v5jaeJ_R3U6 zsQbi}HO0uWLnPulnujcmrP&k*cl>K{hTQzI1~w_%kqHM|icmL?%k1N_@o^Vxsp+S0 zUx3V3Y5Lh5$qyMjetA)=FB&KL#>v~8k+I6V*+1vZL&Yo_A=~v<;hfnSDKUHB^D6Cu z`J7RR$S<}Bl+MiUvlmyv!YY^|t0!wpG^;kHzh;6uPDuIik}Yk!d!x65#2i zA8$>%PZLBoSrW93WY!f6_NJXR@!?;%#2RnA4~l7N?mAf1IzmBGXZ?SRr`EJ0?}6E5 zp~E)|w(ZdqU#gCV+>}%!|K^Y>qkimln@X?pi6Z50rgoIKLpKpBj$tn=%8rT3Kq4L1 zdq0*91iCvwT1#YBeF0sO0QOafu7p^PYsWae?l@L68R7Sm0Y*tA<-JWh56!4TRQ+5} zcL~yQ3ba|`b%35~j{D4;Md@tkwY63Uyzo7G+tRwojmTom^*e2NOK+3Z$umtYJlj-sk_op(m{xI7$PDY>P9M#PAXJCiIV3V^<+`;$l;zp zadWH~M5rm)tF@{OqmsXNunc12bRaz@C8RsbS<6aT)|U|D9|I-sW=+)Azz%XF!lmDp z6XUJ3EofKpo8lIR=`TLJ+;!pA$f~x)rM~KY+ISBliVX= zYsj!@X-pZXlw^wb3-vINmGPGz1JJlJKpzm@Ct4$t|W zYC4`{9JTmC`tjlnL%wo2l$5(Nlw>%B!!*M8arH)&yhR-Plu@ObFxdCDD*6B zafr8{Hvow|tF9Y4*v#|U+hQ@nbve5dJKuIzymL`wWG;Wj{)N=V4uy1?{20v5@YN7{K z*|~6f;pyKSJTCq5o2lFZkFbU4jVP4V;EdazNuD*<=zp>H7Ep0K+x{;E3-0b7+}+*X z-Q9va1b26L2=1;4?oMzBG6W9{Hdx;L&N=^g&;7r1?XA1k%&hL7>h9|9nyK2K`tH3; zM5hd~tzf(u*>nn(pF8uo=GpCaI@m!j(|#2rwHC+VaI}iBx3^bGR7$^V+Yi~w+(^x2 zrS$2uw(O+0rj7k?`|G!M-=taUPU}B!?`}AovS4VI7T@jSc#;+NE?jB(sBro^$7_Ql zkVc(jw6`~`#KPlEe?V|*W6rMiscqJFKlW{?Z(~y8eB=*4tyerHF<+%%xUbFAt9x&E zu|P~F`53iIYZq^G2>7y4)1(!B{(DQ$!O1?k9L>bQfV#dXk%211R{ks2Tal72>lfv3 z&|eq_I+tb_mp%SKG_pEe*Gk+Ul%t=2CaFB{+-y|5Y&L-y@L<^mz1tsVp)zn?{i>)v zC-91};4Z7)W@>MvtbS44$$)bUV4Ke5JshPTjnuOmMjt%PJASh<1RHjl{Z^&Fo*jQk z`-k8}m2O4)BJvDRe%Z*W?WX)mh!CK)Y&~P`Qw8o$y)WO#{lk>m5lC}RR?p|pn@#T6 z-5uiX<=rQ-ZCCwkiNars1<0CRxvJCLh*$8~(;#zdQ}3{ync^PFR+p9=n#oSSFuOXK zZ?8ZEm`0il*5fMp1Mo1Gr>CHP4Hz!dAUi=T%3+{L>FZ<|`EtZA`h0~-2}+VGI^;}bOO}L^R6Csyx*pe=r&T-nN!8RJe}gn*YF_3SSkfLCbw8VwWOzva z`%Ss^_HoKpgmf+X`LYpXxBde|UlC#eJn5#*)=#Xxp!Ihf(m?+U%G+)~L~v%WBO?9x z2oC5t{bp~P5SWpG+Mmi=BlgXthor1&Jp6MIe-)i5ecmP!PU zP%E~PV^+;qGG(;qa82^fU#C3F8X2V=b>~hnx)%oc0{~Yvcx(}5v2N@uW1OgPvSPE+ zpnr8M5XipkALnbLmkI{a?e1=>S11>GU0;bn{*Id^IFTo+!U({BPhSX zF8g>~)x#dM{*4iTMPh25~V!L)1;0_^oH)%XHT(_gaNg@UgS)jaZP5srDP1 z=0OrB!>0pe6!H8o65x32PbcY^TCb@~eLyD*uDLRh69Ca*+($lE*B)AL2R2^%c1F(j ziGsB(KZX5DjI)!aGoyviRI;W<;#eM$RvIYte3oDgYz^+;7ve<85}eN>q`6Xe zS!rvj>3&4W2Uip@ zX;$Ap&|0=RTpn%So2sku+-$HNAo~;4GKFm~r$zMDF18hw1Jo`!2+bj7MN^}X+mkN- zJ;pg-hJ75AGejbAP!IAqUV2?h*=bK&Z8yM1S?m0Wv{0M*apJB-yX1w|IWh`c^>t{O z#j}WU+s@Ckb@vSSk-Ou8J0($FffLBcR*G^lO9o*M)0`eIMw=Wgn$n*cQX)fB=Ic^v zmkXO;`3FL^H-oIRqq8;KFLjnNLY-4md}c;em0pPhW)6`}z=}Iel$bEPO-s;}KJE`;vHiB6KoA0C6ibv7(j-IN)4p$=p_ax@fl{kD_LOAbu z|6A(W9n_dY(v?%pIo0$xt1uN)CpDz_a6V`MJxgEIi6E`l_S@CQ48fvG=B#o9fmw2I z-z(<^E5S;zH*|ViC+5@$IQ|Tdxi?=kI)th%%WTpNFPNZ%2}T&GyOh@ftdkiqTnzYe zd?_e^?n;a9RK15q^+o>|-Zu!H1pWpKD{LB9^Gz2(VH|*AIxm>^wDaAiwJBBi`o3OZ z;koAd6J8sQoVHxX`52Gn-A?uBRH0tQ+5;d>hMB0P?1<&YC?J>p?8cmnA}z?NBk#my zvS^k;i2I5zsJh$)@yLUEzetf(FLzh=m;8hzHQZeBa=`k}S)>Kb5Lnt29Ye_QN#n^hVJ=LPZ+$YXtWU`9+ zjXTfRQF|bFj5>4oOb(*q*eaIoz2m8N<+V%_Nc=i^Jj-E{(N@)jyIDulr?1(DMgL7_!Wr~2IBEXPmo7cnl zkSfqQkbZMn_jP;a5Hn9ShI$~nPJ&9U_k(4Dh`pF7$`m(pZayec;^?Z$6mLB5Zu*lO z@qfa2YpD|X%2Mf6<*;hhW!E*?n@XU4&|?QF+rjyM9z}{+xDvoZFL~gPOtY53m4>Se zM&Wu-=Z**9-0kRx8hFvWlu!hx4(H!qGtEPiW9PFc_d;Pr-AE%f&ly1_UG zJO{@IUp!029%Ojtms?(#U8I2MO&DM(!BXk#dacfHEqYlX;tS%fYVxEk7QxLo4pInm z-4q!02Z^2dd{3>X^mW(t={T3eSuY{EpG;g?R(Kj1e$Jh@IQuz8N+DtZz1EjfXKR*b za_iMtO100CH_QDns|zKjZJVr#{mORZ;mbct3EN95hnixB8wA!>mf14`T3j8csjTrD zn8}Y?==89=WGliLl85eLqu>|qT2ZuxPVSos-n60SlCnvwnOvq-82#W~ko%9z)grWX znJtZyRX@ntUmoV5FGa`3m&5hFXOZX+Q@X{&zkhwh$}|enSr3%ZUcQ^P21n*dGVH+7 zFEN9Dulrzo^7Cd?)pw+vl?xhyXmr)fb`FAFz<*HHoinhWiH{3%aPThmIqp^g_yX*_ zrJOuH5@81A4ugs2GWb_Xy!<-t2pq@{@8#qMN}heE@n#xYfm+H55&qtKnzep$<1hD} zUX}LnEy*5;`wAE@=sP`{XY(bU`vZ|CtOJBi0~FAo%l#mjpXn*gI3M;Tlzx$^nx*n5 zev(H8NqiEDN_R^S+FLnBwPQu^1N)A40xmx9onjz!zmFZpqA@X(Nq4Cvr7jhuyZLo-*E6G^y^T8j^)VuCU7y{=Zr)v}zx@TX#?ifIKEGdYZXpHmbExii2n=GE5i<%Z|_LYX1nF6AZ$rxMGH zp1r-&PV!4z#U1ylQhI747O9t=%$ji6igg!E9+R9Kumw2X78X?lDPL`~oW8j@Qc23F zs5+-Y5%jc6A7nuMz?Qu$V%D?UwODO;5}vvmRw>-p2j_-xCjvf8i&5i=BS55=7CMeU z)Pk+uG{1w#>7}g}#>`DXk*Cb({D``PqZ$k;!{`BYqd7dF{S0IX%=0S9s=_x381x51 zrEe{$y4GPp*NESNl$JLY2zJ5lvc<9WWC}V(7_T|2p`+4flhxjtYU{H+x2At7W$SOKP_23ueBdNU0k<))n;!VsBv}% z;PP}P9%rA{;uJ2)e2Z9~XqmWwvSjaE5J@os#_P`)vYVkovI}?9 z$b{m{Odd*v3eg6qxkBOaP7W>zYbm2hW?HcK#l+s{IS_18tt8_B*4lj*&?M<(o(WIz zocOyMsKJH3GOqI64|_KZaLK)Udg%$)n=AAXR8-Wrj`4j&x)?hOt+RN7B${&t+q9L& za|`*|LER*1!FhqfIt9E!CDoZoRO2~Y+jAluA}0hQ46nUM=csHTZ;8d%+B$>bamh7K ze_JPK$MxzeR5?v-vg8RVd^uv^*o^~MQ#@@J3z3_9jG&3|HN~k7QdbH5RDieC${6RI;r-1s4QppHo~ye3O?#( z7dQ!|9JcieV8)G<)-w!ZOmMFhq~QM_Y4HCqNxo`VM@LUWNl#}YfCkI9Li9|g%T$_v zge!R3WV$|xC(huOG^^d`2#MJFZd$K~*oS8;{@y65gYZ)^&|n@kssb7pI8fY6E7Xt9 zV#jo_WeTE!lzaP@)C5JvKI29U7&-_!LBBQg`vdU`R)@bHY7aVQo=mvg&ZApLp3ASc zGss~zLHvlA$00<{Mt{uj;h$MN<^VEbF6egjRe(@n_s)vpBs%{Io@Sc)pUAoS?Q zLA#41Ya(eqSK&Y9Dk`&F**4>((Tvdbb1yUU_37MlNMU~#nUK~Jsq|<)lXwDHCP-%o z8NR_Z^cMRTiS}u-a~E;8{h&2{I73r zeedUwe*mcS9dCVO(H2oO>aXH&=o3Xh$je3qEf6MFq2BU|D9dJwOqYrn)4}+w(4SXZ zVC5!uJJ6IavCrCBRR}iIy9w$l(3BuzXlIZVjypXc*{pYu(+dMWU%qj6-^lF3{i4PS z$m~Rg?#z1RP{LB3HT!Bnm_TnpSF~mjA^Wq-i)Cm8Dn}Mt1YM@msNzCzI-nP|y-IIu zy_DD0FR6%S^Vw!180=*MP6w80Y`oN0b#%?Oz6o-X6eGzg+y2$#E=6$5IFxM`vED3# z$;LeHwmP%n#VHag8IX_XFOl|CiaI0Y0G_nZKY4v@^5n0KIojhKY0j{vio8~|cC#m4 z>9i9q-pr>2na_+L7pt*7K0# zd1zct7RtyQ5aIYM&DrTo#Vu)l9yo925T~{zf8#Muy|a>#nMK{!Zi)#cbw#s%AiiO* zfGR)Kl}K|BaeHN!y3pZ6ixSJb`;XhmU-F(N%)Y~-wo$Ztob&Y`L?#_?7;%$BBsc#wF@okbFS76lV(5i$iaz>!@P~4${wGtO zR8iEVGhdgZL9kGdRxqdDs-o#)`?2ce0MNd{z3i#N+hk zx-hTm!g15l9DU5zSHO|~l2H_jD#%puM>xO8>k$i}GQ$F1iAC4WQ;FQd{5Mm63)RCd zIn|FgtRU{G6aDAT zoIx%wGH1_uw(R6_3#!R)mmaq|sioEQhJ{Mnzv^_j_}ucNyxpUaTw_tYZ!7;#QsV!s zBl&NwYVlFTYSA$|&==P1v%VzKr`QXt-&QuexZBl&L))%0xo9l+b@aA``T&&WUoG{} z!%$@FCAOiquzl|zUk~SxxGT;A-ES=>G1|&=3~jkT&gj-+=#i_-eJam=Ai)!(O#KL# z2M>-~fhuxB*#1i${|^NHUBBSCiF_dItOdo2>X)@!n%!}x#4;*h+1E|0%5i2_Qrg_J zJ>YfY1mZ7iC3X>3ke?kMC&%WQ6HhseeNC1ff3m}iXh8?1-_dYeJNhxp(!qR-$MOm4 z;-la#@IA2o$i_di>2(GO(;_R^nRu`^=ZgD%2%%J5*NyDTUt_>fz($onDJ{_-PTmjw zhLJ}L?D%B6{iZHa^6oaqk|7u4@;abTLs@KrQyQ*QA?>E)09qe?l4%>W-`X%km;H zo&%hIdK;{cQUUJ=cHiKmw2glxP3K<;z-ndmCh#1k+j=9p)h~iz$QthOIH@K@-8`Ic z@??9rdwL(wJ1fd4%FX3Wm8gB!_ia@1$%`N8Nb}M%80wLpemY*f6vTLE$&-AcR72ed z37!GvI((7*67y?0TFRu{ajR&Bo~m^qL(av1(2iG4_K&WdohPbkGU` zS&!CMv76-3YE%gfU{z^Nv8d0D7FKCJ+q~sz^mEYCapKl0)O}!x$GcW~S)2*SxmRjY z)Ai>p1fHwbvHO?X7%!R++)aTGM-rRFq5{z=SLOAuohQ5}-fh68Hkg>i&1=QZ)VO_P z4tx>8u`IAJId?GIi{V#)xz~$e$`|x=o0Cr#ns#kUVk;2K?Ax1}!c;7EWxw#%E{FVNs@K({t`;hoc^a=z>g5%OLvb84T_M(L-Zp0jTs~YJ12s(&(MZcfFkO!zvak;aW6!0<`#U%)u zlXb^z}%2NOIesry`{v3RFsOL-&VP%DM+S>X%$IYlGztFp0x7qMxO*?3lK4!>eR z99|Fj`We9QtoDwsE|+PI&!(#2v^ceP>~eHmPZp$xAHeBEMfXk=EVg`5S!Jg0+om_( zM32maXzvA4=LUgMVDWQsHjlB5}8wA|*2yS2MGb>Xkm>Pba; zf`{})+6USP#tffV?@VE|quY*0aH~J$66GMxW|fUbTVRpu9y=w1Ve zm9vLC85`fZp5NwWoc*j|JkZ)<_6xCjE$4yuY;?z zs9U+ac)D3w{dF*&zi)BzF!Qh?V`b6w{cOdeYGz|4Ec|a(`m4-8swCy(A*1nES#b4a zG}y@4xH$R#I)bn;i!``~;H{dP?BK0jY=1khrY1KTC*R*nfWP1+<6>q1M`=|z7Yhw5 z4+9oeNof{MD<2P|e?H@1m-vq}O4~VlSh=xCJAzLtX=UMJX~m*w<1LN~LeEQ`$y>{p0Qa zT989R-|b-ML;ojk-4wwh4jVv@4dCf)nASo2ZFCDXx*AYO=m0>))iOM$Df#n6u3&hv zT*EG9JW|aAyp+nP$%xU=nfilL8^Xbp&qi!RLP0FK9*uH9YMaO^nSK7W3nkDEAg z&DmU$jEFPRQ)|SB?XfcqaScX%f9|j=?R_!OppMCDuYDM=G|78;1dQ+8cG=CS1iG`5 zCSJC{Q|c_bxni#`jQj3?ADsX5K`vj`e7TEW56f5HJq^by|AbL0mFl?5%iikJZrLnd z8`3Kgf1XR7no|vIUE*H1lq#*!h!e4z3Y#EXn{v^dU++JQz9-?9#)WP3>QYnDA8 z9MziH!xiWErf^y0x4Rc>F{7}DlHqkguy=Dkpy&Tq}cC@R+8L+VQk1Iw{3GQM1KMn4jWBfWmy143XgJsWlk zmBYC*vM0uvZz@O{h_M~Dn0kf6nL;C@0AdLn<`Se~B5C_M6)s7AFZ55FM9i~fejbpB zhS1N}_65akZ_WZihNlwV!j&}bDOiN9E7u+qX!CGJ(H4tYl*XIQ^OeLlr>CZ}aKk+$ zO&1&7V@Aoj^6EH&bx&lc#hpq~zHwjXa49nxsqeUB+cpTbTUP^{5Ke;oR0FFGd=|Gw z8T>boub!+VP@2PHGTSzXT03`QQH(R6+#Gon3a6LGrpw8uwM>94$c5u#2#x}7oE@YS z^1g-C0uqcI{hz6M#l(emgrUTxudr};>By*-_2py6UgFj zB@Y2bnEQHR0D0wAu6p5>w2=nf!1c7@R${UbF=Q;;SjJ0=zz!kZAZj($mG}@EGKbWg@Kl4zGZpH*7%e)4yb0kkO_GPcyNmY`E>p_Lwsq>>bcx;3UR16%8*+}s=oo9|=$SYXCn&uVTbszH6-AOsilws6bI1@z9 zq+sRbR{mX(eE(EPIH5GcqJ-c3=FgrQ*l!DmQE81!siRe&VBk~IL1(YqjyV>tn65mI zGOr1td&VOwDuq_61c(dbc~R=;z1CPxF%QNLLvVT&9Ul3+K>n zVm#~7NbLW%fZ-*(x4tcyUB}`h<_;VD~}a^xZu~2V+6q3nP}N z2k=c$QH6Hmp?+29GSS@mNc1!0gXOISpR(<@Wvu>i(ldFXpF3sf7x|zA2qT}- zP+ZenOD2*-1KYys?o@VzwB$-u%|EMF;7S3C8ao1Y7fTz*^bJy0pZ1d4D{yZE_ZYoG zMHD2O$X}JR3A>(nO4e{r`6o1NOA(^$; z|0e!D=0_9@yns62!2fQj& zDzL>KdXAH_`xIFHE?R{0@|PIoJxjVnT!{l^L8-yM_aAyANcD3QdD7^bPz(wluHOt@ zqX^DeS3ylCJMwXL_6bKzT4KV#yrOuNB3EccxejGg->|wYbeX1KplK5kvUc-r5V_c6 zd0!~zsq>5W`!`=GTxlrcG#~_tZF5wJ+tK9$mT!6MLje`brIhbveISeIOucLzPKMb; zS;_j=t)lV*@qq74L_O9#q`tp}0xJuG4sca+(mbLQGB2r;A>mSn;H(K?Y^Nny5CO28lahYt@6^c1~$2I zW7{LNuOJOmk!D@1;`bfhubW5s-k+Qq(M2ZHVW;#tDRwBxfQ8ae^~4py91V zkzMZbXp3mcvC}SZqmYZ^tMPt4L#tHW+FWq=q6aE@_0&uJ`Xg7L9VME=+pO$2Jswex z#O^(ee}KW+0%>(KvWy-UDV>=XlAheuflI#pDX4@}LN`-oTswYG9^Z!jJ;tVsO)c=? z48nIsM=m6AfqO^XHWd%$hmI{G>df}>@_-olU;2xk=f1hSVaI`>q?fz7`>?(~O=`o7 zFM5fLZnkQPOtdl|R5)Gx{X#ZrgT(qwyv5NxQMcoR`$P`s7H^b={Co{X5%dFPh-XG6 z0I^a@K=;H8an>rp76vUV#pnR$t0FB6@$y$}(lF46%^^5;TUxd+&4kw%cRSR5mqil7 z=enOg6>a+&uyUl)J`V(-{B#Ltx-V&AaW($D6yX*y7UhTcmhOR-AdlhrE1ti@LkJG1 z?268%y`gDsSYAzns@*EQ=I)CT2F(+NfNPySPU=St1jC=`R9C)t_phN{G&y?8B5Q=x z6@BZt*eT@_?l)if0f_b%YNZqIBG?!-JOJ~Z>=T2hN$j_tFL)HPFZZ4wj|N}h-mt#C z{V|Hb$23VCZOz+C-A{`q?>EHcPdk;~rGe-dU@ui6^qQmrCq7=>_&_+@Yc!6=%qzBL zTyr}u3QLCdzTkzddsug@QmcvrGcQrU<17yS(?EGkk*=nqUUMWtG$jVMrXDaFW6ng) zG6yi_BNdMPWDtU7l_+5-X_LqIITF>3rWezjE~gMPlvyQtK?R*}| zkD*~wy$>~HzLP{S5}Zz}(ZCDu)^h#`8WtXg1{>>^CVa#@6hhSJP-HOTlI6S0P2{x&k< zO1`ib4HJDEn($%4gx>zCG$ z^JX-iVFO*&c5=i5(E~+mXbrD*m#cNYdzZ*6BS1;WLCJ-;I8jAHh{)f)%=PmIv;9GE z>Td(f?o8l;Jc=_kD)*Hth`I#9fUifpbc+4q7++da{SxaB9jCJHoasbV$?}J)+nh8s z8PS;&?>CYmNY9fGM0DGJ%6411PivK{-@Pq5WR$CC#l^cc$9kLb%XiyQv7FCmovoam zl}ub72{m&>x3Znk6uVy;{{WU!uCR^|fw6*WkEElhUHL52!FI5ftV!k>O3V10(I7`j zcSCe&kc2XVr4ge!HSXcz&7zvbV(42#UqWG?gpIu?kd*D6}wl z)b9LrJIcn`RVGWFHm*S`c-qG87m1iOEEA1+ZJ-zq3`xbWC=5-77p#{&JrEI{gvL$T za49V(L6Kjs2@kVn>&uxO3(z-o_rl{(P50l z%==Z}@sJGp^(|aUqBP9zfASWggDO6botI-!klkLxSTp;0m~wO>PvmqiC{%y1Pd^C< zb%lPiCe>CyR8UZsn;6relt3ZM;UY10in;4SMgC*0`B5d9K_k!Oh?2^~m$~i5sAT7l zxb5Q};-zwU!(2qiAVb@m$w#L@{w0^6JUnt;p2bfK!_LzoTem(?^M}rdb~9amV$-?M z;3zC2+G}MO>;Xn>VNW2kYO3=LFrZIeZa93i7jJCz(NE~iu(B=^o1z|xjQ6(DOjJ`# zJ|kK(6sLEk-NCOKkE2#9-xF_8oRlCx`j#M~2>n@7ZPIhrLA6JozJ7JxPH5Lf()g74 z;Er%$H6?p`f`*C`aVR(NTSeNDdOJ-PeLfStjs;eKH};ho26uV<^FwCcBNuiu;XEaR)!8U+jy9PH{|rzfmI|ai z8HZX&^imACXSXxh{e%xbntRg^4Rj33MzF=7`kJIxKkZIV&r7CUdQA1K|Pb1j4i;!rLnk8L#v?kn=>pJsl0S`(0kH{b%~_v>^DTvpMWg_m#UUH5 zm_nw7uifG|4TIeNUFr2d`Uct+jh)z6_Z@BgPQVG;N^XOJO+f9zDj)o&iOaNc)_hgt zbX84I_3R&9QwZMEb>n{tR{o+8{|r|CMn3)ttgy5Gomu>^fE9Muzqkw-wfrYw&`^8Cd!ICH|LSg@cci^Pj;=xc-*g;TU@051knUh^%NB*hebm z46g!S`O$|=rdsukSt#gGsurptwBog?A1C=&kg{hj)#ZKrGsV||J^sbsdw(!;?myqZ zU!Cpj7+F)eclOYSv2&2W)1u1Rhm9QRk&MK2ZyCY3>gJMlM7*Cg4Iq4H{jNP5)y3&; z($FX3lIJJb=Go45U&*g|zfQDi=6L>X@a1upA|{k#re5!eyGhD!cE>wlBXuGam9P4B z`DOg2QZL{YM5_^50%|bo6yY2mdws4*69Uf{h-Mzgy*8c@4INUR2a8RTtn2CQP9jNeJWm2+w z7&ilchSs3xN)2J99=0c{^;>3)Foc%YBcSUJ4z*&jd2q6Ev^}fgP|^_^(slDgw}H$a zw?>EIR*aoQxM2*R`mIa6`Of>1?(1NLxgFNXZrb1%KY{g8)fsfJDRPrw=qR&gjXxOU z(xi8k1aaDNf~}=AtZF(*PJ74z1p#M|iW6m|W9imv5`*BBFOcy_La@z#krDtMQoqVw z;SS1oq@WPYkgxdagY1$|H9=_`#Y6t2$fgfs7@zAOj@5g zRO^sb;ELXF?GXt56G+tvYM2XMdgn2*g;YUU?j}NQTV9UDYFw0#Y2ndG3eSecFcYOY zhZKrw8itaKjP51u3REFU(Q4vI%|R$1S~j0kIvvKX<+h}>X9=&I!#8R~vhAliA;;@C zIs?iGD|NMfE6H*seQ~H-(VYTlR52A#qq8+a(Tol>ci=qBG;#0}2-@^i$Eh7o|4Ek>2 z8rrp)d&;Sf80!oXU@uoErN?K$p0iPvC}hY)$AuPhHZ}hQ#yQtvOX$6s_R>#kFEiTV zOu7S@WXF6mU#iu7id>;5Xr4`lyn9y|MSd`1&$ifAqxE|WiygsI)lILAmVcpg6r^=z zhm$O~-){I78a=7w^ulGATe5lC=_KjNVig(vgHeN!YbMX^<^9B( zqPxg8TV?l@PoC3H1T==e8*P?7!AeNlsQ@gt%!pF6)&7vc@0Jc^T|Y$9+x4njQujwc1X0X1|LJVLV#AiJ8XAj4 zg)RYYy?P5Xoa4bOTwa|M^T*r`bj|r(S-6{kaLyu~BMqo_7z%qcdIGC4uxaOoGvOz-kGCNUTs-omT7-Aw3By(CzbxIWY0JOV#hp5l=zAxAZwHLZ z*vo~#mqwv*BqTD6|K!?}Si!)!lZpCLR#g4LuwK(-{CjnDqC~hbJ+l4a3c}mI{KgJX zBaiQ4WxdD?x8?mxt}6s9+S3--Z!7WwWPza?XV`B?XJVLWQe5D`Z_{&$&2wy@!lR>o zT9`HwA=Slv+XSN2Ah1&G`r$aUhFu58OFLrqDHH<*KfdH6f5m@L+Gz-|k51fFDTgMz zTaW=cc6|5=w78Car25&~a##9YnM=d3eSJCTqpNI?M!tM>S> zJHG-5`XePT+fEQ{MuSuoPK(>0R@xO&)iwW=Nj=HRe{uSOUcnt>Z7_IoKs3_QZP&Zl zZs1VjFsc8dA~_YVl5@c1U7>+V7Mp!n{R6eqtf^wxg;Thu#NSGUKq_iNE2&xz<8|lp6 zvU29f87CVmO-4iWe&^f74D}gS>1W83hLZes*X&RT@`9szccucWPlovv_!u#Kr+1l7 zToke8_ngiOs-I*g+LMqM9PlbI%X)eJJMLW#syjq~1L@4hiaxn+lIZf_S5A9`IyvK|H5@+U>89SC-OQ;b%w=!PsENudxcGAOCHZ zeZq90YOx)5MY8$lf!I3R+9PC^Yd{p11f+2d=pj5xMv&4e5n!_3B}E z$rYP+LhJ-bynD+r@Vvml{NQZ{gJo)ccSkV(!%Wj;xy+y9??S)oVRD8cOmZs)$no@3 z<3^g@HBL%#I@*6b@tD@!$-!##5VWcmr<)VmO^{S-wprPq^nO%UNBt5x@4j4*)gG`6 zYS>epi~5F(OVNhNxr2Aq+@$Rg`n|dEn#)Hd;^AS*d=un`*P^lGQr>2xABt&*td{Fl z-O$rwl-&=^6{IuPvs*g?iAB+eK1of zkSZE_Wl!n-Riw-ePdstQ{!pI#AwY_`w??hTpXTA4t@F_w)J?Z~jXBD`7t0U*$?Z_m zj_+%JS4H!T!;6|bHmUp%90Oc6v%3X*++j#XKadz@TO2sUmZu4^1+oA>v7g(rwGYvE z7#EJZh{|1Y_H8;#p`zzenm3WFIvOscg~s&{K3n38$XD453C*n4iGEp;udl@iEe*-T z#1+ zLdVK-`@C0IeDf*)kuSR~E5e3d9ztx7>0*3Pg!v6jBrV*r}psA6ND;p4`!hovle%=DmN# zo4GG@=A8bKcf~vWXK~ruB?uP2YMxA^_Vq#_I;mLVG5CS&=-3mnn`%-IbpSj^4!?su zS5VZ-$TmRQkzm~y6Wn;14N44bJMM!$zY(VQ{v?0ZL(6V!hHus8yfe1p#D&zs|84)1 z2LTW@;{EXplFHzG*W_7R)y|BN%pas}%0xx_kxnXOpXLCOkK%7IGio6mdILox??<(8 z#`sPL>{%V35aTREJ?%Or+NW7mdf|>1C}O`ayy(K8@rUECLwPZ_@M@m3{$4OVk0uzM z@I9JDg%a*ng z)!^GZC}s98U@M8wPnI;;BecLOcSNJy@KnLdZaa`YZtT~@wEXc6xT#`k8!bK%K3%qv=jnb#tHX)<<&!f*sU zl*1P@YX38T5nLz*uv_Z{mVMl)B29jOZF0FHrU3+ZHbqs= zR`1*SbPCR)W9)F>podQRvTM%>eDHatf3r9_)TjKP!t)b5Lw-;%z%{S4cO33{-F)YO zW}d;?g?G1??FIw7#+)AmWEV5jB-|^^G|9J`*)B6eVgeN#G-abcd@%daW;n_wau)F3 zPYnw(sFfzF*Be928;$rr&u7n(A!6g!DGtTnRfw|JRfB_82k}41fj3zaTPmE8?)KZ~ zxP#_BzU)`$=CShi*w2>sPT7tV8>iZeZgjQC=w1(=W?J_@s5(ZfPAH;4j4i{up_$tx zdY6pO4L?gYlV`_b9Y65}KWlp(l6h2J-*6!7ea8WEY3EQ&`wQR^`=%K%S>FEY>5+=Q zo5V+gB#oX#Ct>%J8Eu0(^O=eeNM%B|W4?7bxYc@W1%i5BEYK7S`Toql$^%-Srts(r zZCuIik-tlY%C9#6JqKY-hEAn>{JCZ3RU;zUrAaiulGs#)X)4$_{`*SSG`*rzJhlm>Ln2w-<{Q9 zXxQW6(5b3H19?MdRYt?t{ZV|RT#gASXn_m-8*V1HD1f~ub_UzvUVk9j zoa$GVm*k$lb(M7~Y!d;9562ZB9}YyP)*cz4*B{ISqz%jS-)`88s+bJSa|=7S&w(`i zXxjj#pF%E`@M4Dn9Q;mG35N!G^yi4K@3cb@`!OYJ{{mXD|4lCO&(Pv;=KsHg7My?M z4F5~eg5$pdE&eL=KY$khuK?t~WD|c~$$!Zv*!cb(nxKkTau{Ysle~Umc(5gHOIfS2 zGLjH3M$=zn!jeaoRwIIm3O!mF-1}-}>ccu?aJh%1472uuA%z5a3SSUJa!(m-T9nP$ zv#VyK<}6z9AWMw;Cxe!(e%1m3n?LCmYSt^!Y?3aXBXT->ylEtVDplO>7-5Qlpv^)v zF$Qk_Q=T7yUJcu@J%F3^9B=jf2Bv?lOHPA-#O>Q53hG|f3(-ygNc@XG|EPBJkC`LF zW&Jb4t)NK`N0=ZOJctKZUZH>a(7FEYM*K|z^w;`7OMuu}|E}8kUwY{O5C#3Gr0TCS z|HVTG>w(zGxY+(y*?*G*NrRyk+uz&h{|H+B#j!qHxp~-Gxr0STN)l{j>}-E;ok|ky z;N^du=HEm^f4?dJW&2_0VrBbhwzaLN;J(F+F>tQ4FRLuY37JgR>>hhal~?Ub(xEQU zp2N3*;pEO3N08d`nR}WISn*tQE=VrhZBe<5Eoajxq(Y0lHmAugL5wRjdWIHBgSx`Y~;P*=S>1>o}12 z#hqR0R(5M9+OCo!!yvgpu~M=K{jzhv^ROj9Nce@ykti81bMpk5t+^YU)v@gxZQoFjmZ}C`H5py`oj`t#9glsu%p#oT!i7>qhg8Z~UH5-WXHazLX*OP^yBx*&s*USh+XH+GG z2RkCWTvel%p{-G`nzEs>F&V}2t;9CW>5wHMt;No{xe|*%$N!RQKYOj6rci9=jmm1C zC0&ZZCno!$s!7i<4Mn&>y1<3kli*q`a;>5>v8w801?t!pDA&?PsXE$-gt? zGn$G-!Bs{yRgng9+_J}gX~X=W7{VeygqA)Q=W;-==#!MWm%?0 z8;w{Pw;Fax19`_dxi2=ZR7D~-gySxu3vnvr;wqewv$C6!uBWcsDu(mXvi%?O_lah$kqw>-Vcvgdeb8aC5Nm? zq{ENJIc>iG+}vwL%^z9mtj(o4FN^|4m|J_%Dt1;h`_bcdz1yeEhi*p_XIU&Nc_YV` z23HqJ(k+$s7c!wmTCS5k=t-2jZMqsvGQKn-Wd67gZ<>v;JE?1=RO^ZeVm`z(SeD&8GdPCrxXH?LqoXG6PfK)-Q66&b4Eb zo2*o>%>rd*QyXbm|SBQ)>)RW6Nh(wY>}J)Wfz2`DuyFzk9mF+m($O`+%hFF}uF{(uM|mFcvY2 zOgVwk+CRTq`E}UnF+@1!+TcFFKd=JzCxXQg5LSM}rUOIQs9bi#EF_8LIs4gL)sFUk zZNc?B{`>oDZB{R`xZUdQgGLsq2@x;U?KtB58JWUb)|a)5OH@yIZuo#xlmve3hTjwk z5j$UJnModw*EG7EX&Ex0op_2{S(LEeEPzFiwf}!?ta^c>^;IA{C=%cx2gp} zis2};Z26TZO9Sirg~j3brKydcE{h_c`4_(o8(lj{*qTrJni2MYtQ4pC%j4R`)m7x= z>pd(y>z_Z^eveD@Qim$Iykcbk9#I4*BfB9t!^yX`jm<@03ClpDC6?-r%nS&XfI3+!(AJNWy@Q&nF2Z{^*q)? zz&7G@bTo`48sQa?P6%u2 z70^s;w;h}1IA(SGm_-Y>}x*U1q&MB>orL0M-&?4GP*AWw{7TK;n z;TbenD|438tlV)DIsdQONp>Jv(N&YXg&TM_uosk#m{;Vwc%*p;dXz8TQc$xizgj{2DR9ttptqwAv(`L{ud*YSG73$12ZjpZwc`UiYI4p6eO^qQ>L)=g_e_Ocg z4z*eQL6=Z*caPd-4waTVfK`HI%s@4cBchCJl4#FK=G^!vHA2Z_(g^%uNmd+O1z%D- zw`zfx;h3+cv5c^3z9wJCbzpSS!*&Tq!~*W{M-)CyvSeh@-B+!ZvQW6C2?x6dMkL;Z z-TL%~Lik344Q-z)?@R4=Kx=bN>idW&mhqeNX{^s~R^ABa`<8*shHJd90FK5hk7|cW zv{4*(39`7uXK|4k!ybMfZOlV;dDo9DJB=^UFD6h4F!#zSkQuS=&K0k z%EHT=s%mGDYOh*Rp(|Wh&UAG!2|J6=CuCkV(P;`+91m_$Ca^2_x54`BmgKtP(#{aW zIEWYGUedg@YpSHZ7v@y{nd#RO_&8LPARZz~SV|d?HlZ1fUNyJcIl_y%{CK;^tJJ_) zD2Y8P<|}tKBIf4saZ`_8eo}}PTe9QcSL4^qrM~LsigePZm|t~X+59N}Vrz>ELU!Cu z3yHQ?(Ra)2y1bXBoX2{q6-n6b;o;9k6DQ|vvF%!uE#nphr02}t2092+dAvPR&e+}b zhIMCpjbDi{{Wx-d$Vl+Dxxy-GwOCyb*P4b!v(3lhQX*N&fLHaenTjlk)1x zaq__9QzC?!&D@E9oJ0T3gB)UGX=wrXfQLK0>vM8|U7bzLEPz~WVCUa%@%9#$Zhv06 z*jQP+0l9d=uJ$Ib)<7O^usB!(ED44HdD+0yKwb{8ELaZ6%L7&bD}t54%3u{B9|u?s ztPa)y^7DdCz@}g`usPTQYzejkTZ3(Y>}Dr#6Vl0*oo0VOvGq@QT^&7pZ&#M5c4b(^;lZ*--z#`oy^L2CQf{f)oq z>X=`9*6mw%o^Z~tt}Y`XvX`El-2;YnQr;oScs0)^F~57@MnN%R)UOWH!H?SD+A}=B zFQmDjxhD7L!jHA?MR+*Q`Ld?f; z{QyVd?PdXE3w>&pex)V)SB?|*x93^|TC1+?W85Ow^rrG*T&9d0oPFP5o1~r5^$Wknt| zg?APwpQ{^hec0BzqtAj&7Va!SiqcO2srFe{TEHOZ4CwM4rWmP~N?+j*YE$=7A&HUC z<7X#+Ic^oVO4M-Z)!`y!?R|mo|Jk4UmOL{HeW?>8%+`1;X!i9u#c_t0$FYV0`L2=pgAGy1G_VOyHT4hF7zyw4f?CWYuFm@Pv_YM zQHkga&s(Rw)r^lhT??nrx8~?XN=62%n-$uac39?hl1M!*`cjO0iZE^laGqAK-?F!M zDK;cpiese}|A=_u6+x~4NGbh*j^RNjMJed`iyd zo0dT**X@bzLfe~`SCw~a`%4#;n)QK3!89VCt14X8w&Z>!l~2ggGUoo}+#ri&bC!+? zqZ0LwdZj-d*#}+7mig&m*0|`xQH)_z-Ky7EktF(?|-tABIRRN>Ecb#OvjAWzpKS|3QcLpe}JRAFJ%py0{7jf#gIPq;l zn?^=W?afvA8ec;M!sC-c?BUm^;?{jWy?7~@D_Cuiz%XNV&KwlBbGwD-Z9u9bur(pM zmk>va_+rWdq*}-&Q4izS#XPAFRTP!DI~&sH@RE%ZywU8OQo2rzy=SzVxISo_oe9x? zXsY0HE5BEty5zZQ5)oS{o+s{)N!kPOei9p=WRCAw{`?-&#Pw56udGsQ>~o0ZVt+-> zHy)P&)YVd>B7;w^vRoG|7nqowOhh>5AoRkk>t7g)r=*SsNH74M*9X&_X@cttOVdZ` zFdo6lxKli=M`a{9blUsZtn(h2e zgsV|GnKhv|B0&9HtcOpoKU@&31jQeFt$UqLCa#Hp&bZvG1f5{>e>%K4Fc zOxLrPb4tycm4~ptXv7Cy-l_P&IlGm%Fpu2H^MY8qYByDFz$xPBUgdgVF6p{5g<6wx znM^w=HS8n1RWteqH~|xV}{cFgKR|@>f4zN0Qv&XD3GczlXn^!DBr@& ziCm3@d-FVFk{x5eHne<>5(@EERbiav+sMn9`mm*HKW9i=kE_)foE$^I5vYl&8qRo4 ztAfGR$XzcJ7UffJU2Y}`Pl@5!WwZB%-&gmt@&^#YEh?Q*=95lJ&epu7wKU@~)1XqX zMVQ#DFtLdi)*$;nPp-2eURm$OQ(wRVohyv7p}gK>jRS4ty6oGE`4<-P80YYQR!=)! zz2y3?a2DnH2g&ZrcK=h?i}U!NB~(8U??3>)U;@3s2N?u?R#Pxrrf_6$!pFp|?}XI1 zk@(CEeUnU-)JBKXj7_#_E?&+R{&Ox*(#bRk_)xBx%%fj4jxo!LY9~cxj#S-shxHd? zF6AIw+oFc)F4!>&o{kR2qS-Z?F}!++Xi;72w|x)Y@1FaGonNdA(Xu_Q;++uAWT)Eo zT1eF0m9)1V9$!(uhFHq1pw1rUJv}LCX%Z?zYWtWz?N21=qnDN@zxin}?ois(vm2ve z-6oVbe`s#6_PiHC6d9VDmXF z?wp2y55mmSK0-%1N8)0Ixnb>0vcyt)uV7<}B>X{cKFLU=^ZGNb?UpVz7ivYn(^l+8 zUZYjhN?$CsYyFXlX-Toy!d%M*&g^lq-41PnIrAh9#}C>(4e-*M6S+%+ zPWh3@If_StHdQr_{VQaO4@O}NN1=UbEoGTrGIq%mq3--lLqd>kr0ERpIrrS*9tORCFQf`l~ajE@+t8OBp)wWWA{1sShyk+(IIVi`%)@sW6aq(9Hay z)zb1{TGDoltUgW6dEv6dI61q{gYkN`Gk67!y!E+2s6mj6MlQVffE5^`I!E86=@o?K z*VPWiT#=AxYWXEFiwOw&M2F6OU(fJA-r6MZ-zHtO2rD(*CV_;qBf5QbbqLISN= zKmUA7vGi53s@v52?GIZKN)^HZO;arz1FN#SMwRS*Z4=B3j$}RBW?yIJ>mRc=_T70O z+yRF@(vGyR9>mZe0@8;4DUV6~=x@{^PS)idW-KF@qLyEh*WPg$wh~P3 ze7^93dx%aaWk)`b5s#};@6hjvn8uuLDy6@Tdf2av6Bjt2b$5=mU4lDQq&)LeK{^a6 zmej}yV#2fAT--_P)H8oVT6PD#`610IZ!4PR_%3kN1$T(0p=blg&qB58mFy#zV}$Z` zOUw)Bp&5`w5o=OOPc1xEA90ZD}Rj){S=IoXB16lHB7OM_tLVFCg2$j=Z8wgV z2!)?UDMhxO7u^r;ES~jA@$qlfuT}&eAybMKCjr@XBhX3+W4!B*>D|lhYu+M~ zcNKN9K7I{joUh3{7X)k>o1t5pMQsodxyTnMmoyR~tsj;UYh_`=LmpioQfCvx>izgjA) zEE1^8B*|h_aWOnn*WqR^S;&5$Bazu68)_GYHdMn7%WjhsLlMCt>0v3gwwyS@Toyh! z;;wNGB68D1ep00TP2E24xCHn8&!?*OhHhS}l_)DIg)0c)d`@)wn`I>WYxO;f4`|Iv z7kQ0!U&=9^O6-a`xhl6(2up@+xwuP7%C@L5Y2%3(rl0!mq_#cuM_1)voH>8|R$p&oSHD$*B$4EWc%>8S&Ok9s~!7v3I&mQxKWIYq?lv`tZ|^+Usp>AUp%m z#WM|!x3y||1vfh%sHxiY-E+jh7w)K#zCq5xn=~*2X)(8JQ~*s= z6Fq$Eo{*B;zZp-amAQsG5YP`i=C4bs^QTTL*KTw3`>b=Gyr9q&Yf*4O4L8kP!5Uy^Fa+!axAe^6hMm=)<{#X=lZ6|4rf@^g18$^QgFXMz zTm(xnfFTxtHi(6TlmB;^vXv{4>yKb)iQj?PEZp2|Ko$;Oc&Ic78yDOrA&rZ(rvB>V|ESg10%f@Xm180!>bM~<2 zGwX#%?l&*V3Y7vG=|VUnttpqDwNPbPQcQu0`f^zVT5>c~?d1~iJL@d875EfGxh+Fp z*r?+eWFezTLf7zrEjr~xkg5#64A_%3 z;$_eb;WoX4sB9MP_8e);$U`O}xW2ZPr_}wUzWxq#|6huqi|4<^uOB3dJEgPX z_Z|D84K-ugXX~OPeP&gi{mP-~P;dn(cCn|cGR1g8W!tk3Qn}*6fe%qTh%wG}y&$ zjEx#y<}5x2f1cd6{XWhtg*h-n6MYq_ryBjPb`4@B<$_djvWnO^{*`UY(z|m6QuIpEN3HjMEY|#izXorIn9UM5 z!Bej$zAQk{9`-iv=a~{WGJcu)6+UX%m=BW1-se-)DA0O-*!5gXYZBm-C=8!9xd;th zJ8(lGO}Gvha>6BR)d@)GcJaCU${4$#ZN-qBUSOBiGV&vIcQ0KfkI zF&G5=gT&2F7$pAt3!sjo3Q*F?#RAC9%Ee;F#>Nfg%hF@?q!^cW?4lp}An4O=6 zolk&^TY!@T_}2?0f(8_FF}D;@gGm2X8T?KdWbNkWEC2?3dU~>Ya-2Ryu{so+v z^S=?pIV&puGx@)GJ2?DV!rV;2(#gfa1pX{0&d%_k6qDb&0)}(_qp5IC0)Hr^1q7aI zLl^`XH#Z9#2mDWijbDHZ{>RC}#v{PS_TQX<_o}m1JSKmr7ElN-f3rV3{BKqJ zOWD*d-u!v@r|#L?h-kx4M6$4VUi(nJ|1{t~68Mh<{v(0^NZ>yb_>Tn8{%eL0 zPedn7=lOg7j)wM+_RHVAQ~xzjgPSUUxOo2E+W4Et=pRn3e-QlLbD91B!#s8z?0;HMeyMOX`2Fp3X zbL&a|`6g!w)=@UKwJ`ggHc!rh2gt$kX9T*O126pguS|J=m+9Y}8ve)r032N0{QqUT zS+CUUEXFT3{EpsUgDsIvKJBnuX*u<=Q=d2Jb)nG|^j=d*fa>J-f_^Y;@4GgUX6K*s zB_@}Z)yd{g>Jb5X)DV3ULplOk~U{Ho# zGHn_2s;u}&)|6wSWh(1TlRk|XhgMmZcDvNeyAO8PdvSeV*M)lJU`enjMLme2VDopr zo=3e$o5W4p8O&PhL^;J}qPhT?z2V$4T!+V>RmUINmmf8`bw8~%X5QCjJ$HXJdhl7w zxNg1UyQI53pLe+9V^_3PSbzwOzOf!a?i8e2u}SCQZl+UK{KS}9Fw;{93boU8?B|}# zuA{L#dEILFalSzu&*cKZOR#Id3HmbBC5MF*~(zi*LKXd89p1e^YKwzC=-#1 z-197^_M#0A+nGL{Z|?(1_sOt2%gKIqpwI31^0TU;pLR?9s&!~K>OqaQma$iIpC<3C zI=19fa&q~_z{8)=PrS^`cx`MJ5`_EKc}b;ZD@R+|F{2;Xug1JTX?9Qc;sXNt4yJG1 za%~tmoJf~*<%SR`lzTaQZmsB)$ceEgd%|{w~H~*1!i2lEf5&cOBo}wuQA-&KYuz zC?WxFqD`^N_5<7dH4(p#Byy=qVK2Wr2=|L8WJJ`cZlQ(Z)uz*=Cc?}em$3+}PN;Ga zKAI}pDA3dIRfXpXEJRTe#LhiGDm)N-zD(n+e|I*~qb6!}>02+DML(ezA2GKbxW*T7 zBcQ5u@{rAQxOCRXl9hLw_~hMtCxhm5G`&{<+>Urhji;0$F9A;n?%nO>ca+J}ErZS( zD*z0~9yC1(iESwzm@m3j88Jg?5tlpMy)tETjPy3JgJMcbP$fulL#SH80u{UHR?8Dn zpNI%+`KE17{8Z(QQWNbfP(yqI zE?uo}RT%pbx%gY_a*36SFf_@0qmFzO18b(Sx1_uyj`(ICR=k)G(!zM=XkLnr7`A*L zmjYvrEMrqcuWXNdjj{`s4Iivy2Nlnl?iRDBNYy7GR(O}-` zB@fKP!R`taR6^z*3vhR(EUz6%d)v@POch|;91K8;^MY>y9`?&<%cT;b$_kSDeYPx7ITy`!rE~+0olJr!!J4!WN29 zQ|OUK;CGr7jB%PL!_woJY)WVg=%(q!OyH>GCLTWoiR$;4;h>p~l;iJ-@@NWjbSB zcK7P#OtLj?_RYGs$vc%y|56LD?~xxOkDr<8f5z!J-t=t)4(WSEF&lmxIyoo3UelA- zMwn1x;_g;lC#*pS88~0tHBiwA8JT7c&{#KZeu7|*G4G2T&+*>k5Rd4nJ88YtK|BXU zzAPIw*Iv{YX`qq`@>pF}b47pEl@)Ll)??7f?KNuXLK#^%%1 z(z)O)`(9OB&rAHRGlo&w!TD=E^pEpMtq?RZMMjEd+#~1fQuv_)W1M_^Z#xY4b*@BK zbV`gYxxMOtcs4_<`c^M-gcFQxA~U1P#LitPJ_JzI6KDaNMS@XhS33k!J>Oq0Xc6vB$tTs0 z#ou>v6`(@8uRnN^>w#GBy45{7;sNnRHtqo;IaQ%eA1JMl#^Ph;o@2LNOS_JjcjYHP zO*e{GlK)xfBp;x&*_>*?fk%-D-`;FYKmBUd#ArOq*p@MoDOqMiRZrivCL47kI46hQ zD`mVL=&!JYa29d5=)v^sn(lK>h`cQNVW;=60(1_?%@16V8(%6f=Ot1X4VQQHQGiQS zmM>l=RdqjDv0V^IoidYDya;X$1El$mPpOk6$*K3iWZE zo&2QF{(@l}v1U>FqdkYOSODK&)kMIMwRT?3ya3C;B_WEAQ=^l?-FT-s_t*W~LMpbn z+$}?PdIV?tg=SR|KfNU9lbWm+zSbYOQfZ6n)iy>zFT~2rZ#{i0^+EB-)F&RhPr8gP zb=>mbpJ>9i3*y+TuJwNnp&4%PDxw?~UhbX0Vk*=M%G0#a&DSkIBWaO*@}iuvK;W_@ z@Mm^!B1@G~LBFdBMi~<7ZFO4lXZD8a&$v^{Ay!76A_ zr>F`FOaENiASx<4JT_h3(EdI(*DEA8Ffg#Wqc<=jAuB8E$M$YeL}F^rXIN_9%a<>w zzb&R_7Y9KTK36pik56xH@8uR(Ew6pQzP_nxXg@kWg~Bqr`$uNxmW+&y1Ox=0JbA*% z$XHWTqpGSZFE5XRijIhgD5q`1CLj%@W7V|_mXnjCXA=m?XmNq&o4CiQnz;MKS7Ksf z5|LB!L)2^oQvrB{@YVn4&!00fF^MY~@$m2z78c^*;Am=UT3T9?laqr$AWlwB2m~T6 zElof`Kte)NU0scaj*ftcXlrYWgnog(LMFDmX}R zsNi70p@PE(2kB3E;5flygM$YL2@V?^znPgCI52&EeZj%O@Wo4QZSBU!#?#YNF)=at z^OuyAeEV4- zK!5BXh4Qz3X9*iOR}~8vNhb$qCwRU-Hy|JQzs##w<8cX66*2<0<~a{!^-24OuO-e3_>#iS>d?TtF++pLQpK-zUmXyUK2yjuRab|3@Y+ZoqhGrD{nHqjZ%IP zoXr&e)GqKuP!&xxx#mlx;ybUwFavCxv!#|7Qc>v&{@LVJR(8e~e#z3iMO%W5PF7!o ztb>9rTm4?~ryTbMF;{y=$|j^-3@{!Ft0E&=z45KUu1#&VGnR@d4v@HA&tP=&j3;7% z&bmGbbaGIgfTGmE5wjHB;jtaNe( z+0PG?%E=8C!c%>XqEA!R_Qp}6&x0Z#X@cnn(PfwekzxC*a zb|XvaIfbPsQ*o%P%kXqq4tKo@ujWyt#myvgLBRda7AVQwR_jQj`^HyfPZh=!QKNpu zT>L~&%D1mK$YBZ3t?P@(CX~7Enh{SwvbAt;eIc0^8klS>8dKVkxspV@N>CD4ODQn} z1QNbDvo{B54ntKB&gFaWs98|wxC45gmRNIe4UrGw*N_%N>2kK{V}0FDW;X!ftis`8 zn{2M&BHeFWj>@j0Ce(rcjP`70%H+WZb)NPe=5n+Nfw!gvy0*uf^vq;qJ56I^v8BZ@ z)R(Vpt9nMOMk_;Fu`zpZC;dV#sp`E2y<4*E;#EFI46eS8d66SwOW^qh54w&zMU4x^ zh(7h~5MV6Ru^LE^9(FlLR8U4Wv3~^_+{fSVLV7FHn_eV> z@L;73qAkHBW89HnBaMsbaW4mfim|9T%(mNtB60n&9S%RZEHPjv&q89TtG36uQUR$$ zTisa5_U@|BPq*A*j35vCBbLlPAKv&zM(-mP4zAcVyht6R zkkc70rDa`G;y`C^9Arv02Ns1?Vt^cqP2Q+<$0S3Wm@&l0)}g~Agpwj>6Eq!sX(k+! zSgp_ss>n61VT5O(0r&jJDOg%k{DCP)k~^* zr%h_#CSvSZF6R_$XJ+%7G?ewSt&c@^FWGqyp>td^=5Jf4G>^o!oQ{c&yD`EuYCsJy zKK0roQ0( zAPb!2Ewtva86K*Tc8nP)!r`~T|G??(7)R!6qPsk*@_pq!BELIpaR1WbP59GbcFz}6 zYTO2#GEHG$Cejbxh(5+H*G^8}O(04677Fjfvx=Y)n>GS;EstB8X65$*{7IdqeHk)O z1wb}E>@wx9b_bd4j<08-V^MI1Pns;p)^`O4MJgeaUvXoM>^j**0q+*@mTcg2KQ$(^GzHGGnIVL^d-=3An)mJ zk$Q+n*_B?Hdfh7RR8cLKPBipBQH+lh$zfLe%}3a$f#_&VfhTutX$Q`Yht9(>gLgur zxir+xxtML5(9JDapuzkh)va8&zL{&4Nb|w-^hK1zFXP5eIb{(ApJvt2Tl|X&ico3? z41jrC$^3A(ciyjA>9-CINe%Fx>&2}KZG7ov+fKsT_4d7XeH-%v8qLU~oUk-{Jr&st zaAh3PlmrYM8GMVG&x*fK1KKA(bAzOI{x7@q2v`*Vb8R$*chH}WD%dS@TnXk zY{5k_mo1q~BA=rEynQgqE_d+3LbLupm;L$XdkU*3Ao4uJ57iX8?f^->`@9zq(U^PB z_|>QOO)ZB(niFH=699hOce4I6V(t^lG@z*Z=1DfcH^F0lvtI!G^N_~|d#A&t9oN>e zl~&Ic|6|8?eYi4Xz|1Al%beAr879Y7x`do&1jUg795R%X4$%JTld{O%EL#YH<4d`` z*q&$X*qI10@3%dQ3Z>!B-+WL7wT%Q~T`1*ENmio`^7}tT`^(6f+pt#WH)He`CpNq* z_};jvX`>8mi%60GEP7Bq#I3}H&T^bL0*`siynpG}5O-;``nwS=Rs-*<5o^}YCQn;h zv4@dI`lZgeygK&nZCznfzP!ZAqxu4lE9DuGo?UaEwO#DcA0&CAE{jNB`)dT>?*R`@ zn9ypv7v)hvx+%C;JWEVm!5ea?4R?h5ZU*u!Imaz+?NB!*A$7C>bVb<3kfN%C+@;+f?gsFn>h8P7>ErSy zPW};Y+uPQ(D2J0?@$l4C^X{wOe7-+=D}Q76p%<>l9QeDp^P{kU_tN9$dS~8zSbn0Y z_7c)FU&2#yV4g;BKZmdK_MiB@5$+tt7IH1y=(^l*36WoST#VdmPXE?#$7$f>*BUq-BH zsiG>#zMu{^FcT`GKt63Xr#uu0e<0BTt(a=KXrqFxR#^ij67;KErk_J{hBSXEP+S+U zY#$XOD~sfL`CZ&jfyuVdA0Dtvt%F}ZyT+oV@LTK<4Qc_3hu68sq%zRAo+NHa}w&uAUEIj^i^rn4*@#Ep}xnh zL$qY4qaYA-CA+y z-uQka+NO!^<)cGCyV8q;52KTWiHdQcfGp&K-pSIL_$If=UKNeK z=8b0b?xwQ!v0`R?FszG8)UYXDkk?6sayCe0|x>-IKaerw1@>WD|rsR{HKn2B!ct3n9QrN}WgGg#t(-6#JT-DkvJ}~-5rJkf{sd5nk=D0M= z>_|z&Qhv;$b3JJaAGsc|Kb|mV(!OqP_Ur&ZUY#Ge(KjOCoz);~)paD2j29vPDxX_H zc1UmvVqHcBC4b;y7{s!Y`7WP8$5ZzuM}Ozk{3xBZZjjP_TOEhdY~_#_A>C;D{6YK2 zw_*8yCWl}qwOotyR$8ffZQEl8W~*y4k&gnCRa~SwJhx`Sw4^(SjmO^6v8>l+zSrFx z@N8+u6n>8**I5UFI_crm@Tb#LRZiTZ+cafy{$9=ET+lUf8KmdEi5Msr!!^r@+jV)j zi#{CAs(zTONG|Gq!)^?%Gghkmr~Fvn1UYN<(U<5oVlRXnK^bA zy#I!LIR#wu<@MDOt8`|HfJj#*r>z^KN0$cvrN%D05V8OGD#1>iftFC%bDYx9Ah8-a ziW%EycIVp7LLDa6X#yhL@@{QD4efyyo1gY_KQiJ-tQ>xN<`^;`B(|TMdAnz{_1UBN zqX3%!x%K1spK4#Urd>}Scop02Oe9$Ao{0h9AEw!5_3K;PP409dU)L3X7oQ#n=b|yiCFPk;>p2usUbfyIIwVt;G4GylY%1;yz zlxjlC#TJF=ENSYy?$U`NH2SHxc}6_+5HfX-M&1wU)=Olu(QrmO4wLf@a7E9 zPjTRx@=W}gp+xWXN57QE6>QO)i_tUv4xd8_0z|Gtt(UM-?l3G;!yA!>42{f1-$F5( z^0+J^?=y;zQY-D@#lBMTKYS?Kel~GPw!WP+5h3&#NmetQDLpVc+bVllc#! ztyp@mX`Vu#j+AhVQ5XB#;2O_pHIvcvm{5y!%C^+k*B8=}h(6dq!n#Ox2LnKnJ`}U~ zmwx9D->~O3!veDs4mJa90k;!h$FSRc@Azf*nva)#$1TzA%e;VSzqz`L<<~6dA3am9 zv;Ay%L`LQpnX1!T6utdEP9yS^iJzgAVGk#V`(s3#Yo+H)s7_<&LR`;-09!m<9m zwwt3NCvSWIN2PF%+rXooIWi=5(IKJ{>Z3 zlozrxU;9JbW|tEianB|`=VeZV&9UQ{UI!W?Nc`NE1t3RYYxOWHui3oR6U3REo25l~ zSu}q4_4??X?RM?^!$au8L-?xDLt5YL@sjU&J3%ERNOrtM5Braq(B)B}@5hbK77D+H z$AN1_R*js?=3{F+W?#PE03CIyHWmA28}vDl7`3%g87hb_{n8yQm|W~Je{cWzVgBvf z?YQ3FsNg+!m?7Vnqv~g+I6z#kirJ^Ink3MQOgg&gU0aok`lo6*)r!^qy>X!Cn?lJD3n)g%7Cc8VL-B9xP7*X=8K5GBTa zBicB^a*xLQoT_b=z4SuvoI3o7su5!A<|=nWmhms8*l)klxX(}_f)-sw!W@%7dXYLP z5cqC}#=lLg*rcu$s@38ZonH;ipGgcnO@Ir0R;A8~W&D>Q5=h(?4KSa?xMzg*yMo8l zUsQQo+o}CPt#`9(o}wM>UrGxSh==H2){^Lho1ZNZ{uU$xtjq?l)mW&(^$E+(J7oB9 zZIQCXT$^-v!CAF@!c?{N@a7@ECXS`@>2Fnl^G_>x$caNkUNxv)kUHYGC)1OkID9wO z1T9Oi6N{_--7T2J%zYV)eRXRW-h!w5$M0%VbLyI2D2s~ndtH&om5CbI+PAh4=)@wx zvb~={?N#f?zenuCG?|DvFV+l&!V_{Xk! zSORY>IhwO^pV1An>gD%+v)2?lOGrb1k(K#m^IP5Zh0L%b3)OxUmG}i0k|(oMa6u~t zoKGPF?63{1DTl+U&i8E3?fUilk3>&_xU%HQe=|6=#cO2{G1^zJ8`7-n7zt=4`?LN- zTbY^Gi_Z(s^n%a;sA<|k{Yf;}@hxw^(AwFk`8y*1R$w@4vp6NbySjDgwFobMm$M&B zy2OTkz`Vfzd5n3{+q9q&2Op6j6jw!9FU{ZHh0AV}NQ95xTf0_&$(&pzsHA`a$20aQ zL2}DO`u-&zjUfbcdnV`zAaT3xX#Zh+d#dSrTS99@MtE(@)AEp`pQLvtt<41$EC|r2 zW$8WCE;f95E(d)mwNnT%jBpeDwN!IN*dUTClq@Q0A1C#PSep7R^Q0UA4H4!qMLo;L093ou zL4@UH6f=j(wlB3w;3p8xxlbb>B7y9F^Kols2QggUXoyj|WJ@^U!H5TIDwe`zF5$;6 zizyi+!h|KLNyk9;^x`^V`P#w#Y)*_Xpk!EkMkRg(#rl!!esQbqw#x{RQOM@Z_2laHJ@Xe2eA8`14;Qb11Uz``=j*1CIUb2bbN;S zS#U@{_i}i^IzqZPWTPSY21}Wb3|MW(Ely3`1$rQoHmBCL09E%_xD3sWM7`1!=R^Bd*o=aVA-qv=mhA6aDc#zxXZBL z;A>JrHYm_9%!puK8s}khyC~7-Pmkg|@#0`-Ej-puOO8eByLqK5y=k1C1ZkK%X)vyy z?2}JH{UWwB0OBf9d=O_}%q_hG&?SEfG3Jdd8LnC3_E#V%&{xP(+q>v=u5dM*#orcc z9?q#e=gWxj1bUz|0w6wX%z4)jDX4ab_~Z&uM)!p9iB@2zJ;?_Y$5pH0!af#tt`Y3y zZshU+tK;-gA$P-A?hpYGTwn}&q^TujX^s71kGeWD#6-XH0I4MP#U~hm`KmO^$@O`> zh<-{beb6JorA|Rn3|US=+GB-`i;9?STUwVkLe`I$9R{N=vdXUI9Yux?+gac+NH{!! zbumk(TEB7~;$HGZgL1VgQ%(*w=bSK$nfKX3`%^A6Vr6k`NudeoPHk+77^#i2BG%Hk z8K$N>2@?5MOIl5zFrf!|T7)o1v6ydS`6mR%v>{7FlrGfRH(R_2Ai-H0zx+1;R`>Y8mjNONX*8k0XDJKKT{z2LI}`W`I4Z14Af9w968BD zG7y#H;hEzW5_@c&+K6YZ!t{GB&l^k})W&`$HBQK<+ZPVf!g}C&0IX459mF9z_-Zkq z4iPqM`vS0gI_3?TRPnVgw~h;wKhZUnH3TNa0#cx4L#dLSkgmup&0=Cu_#^}aP9+#F zYfcnK1xS6#MWsn?5?ie>0}V6Cr>TAk8&DZuLW5H0e9_h;Bu4p4q0VOs(o7f>6a2y2 zLulS&2~DWm4eF1bL4oD^qQmJtlJqA$8iO(N*)cOWvKaunL>8%^aZs5SlKMR$cT}1s z`jC85phi>k^D&a=db9G8b8UB93_git! z0;*blGK*A30Dtf@_iR5cM5%TR2_~Lk+lL0-46eN@ggQ=AE-DMY-rlv`&xsR$D>FDxC1+F+hMaQ}NkfhznSH?boO^cfcX$8X{dRu=-PP6A)m7D1)lEGlEPU#1 zyQmgrUJ{o1Hy=MlJmE_3x}C7T^Ft#h7Z;739JQoY|4X(QYD%aUaU^FQkg%SHX=Hdfumg=sdgo=r zv`G$8FTI?72aSmt9zaX-WG(18ejKS)Cs*xlUqZRkM}Wv2Dt6W_;s@m`7)VLRD-7fo zobkdhLi_e`nE(SGbqkf@55wj}BTs%fmsdvFe!zzTAC({tBB) z|AFWv@gP5Y?QJhbMlvqJSfikygK&nxtM5Spl9&AgYD@?Xq9fvx7ZGz%vmdLLYQP{hs-s zQseDDTmVjP6;cl$H*zEc*E0&-OXN}u7h@HQ7eySSr@?&^#cI!M@JYt+qr+WL%-4&3 zH9Gki>+b)2NMC9Pn=k+hfp8A5@3$NQnbP0YoV!bu6lX?nkRWIsDHp`==#R_$N;l7W zZ+}d^r>XGynv=TlOfJwXLOSX1e)>zuUUI$WxB&;f*>@fkH_%&x^M&y?4$L(@5j#3R zZ)(C&{(6jU84tEJ>;!uu?^yO@gX-lV_lN5+*QuYb3}kKN_SALOmj*C@3)NDoMt}4x z(-IBX{XP7un`ptF^LP&PKV4U((V@LxpF|t~yHh~Hc&xu=CHeB~E5$+IjW8VhR1jQ_ zbGbL#s3{m$hk+e%5dm2oi2tZE$uBeEkLjVAdI;Ohv0P6PqNC^LQX&ar@UYO%0PJ`D zHwUSOjY&(nOWEW@wJ>tgml6RBF^LBO4Kk?mE^{0-L_m0$kuyj!W*b5|&SLgCsMwCUHq#RxMsh z+?g8EC2U5)my@jrKc#QQ@!u6MBio*{}{f5bRRl!0s%~3^Otv{cpgGq zv+&t*-Q4#4$x&407C@BhFgJ9XK_DVc3zl&x0-ij(b?H0YB3W^H2OfYzBjfyN%Qydl z6QhtjY{H?F|Ds8OQ9~&M^(=$`f&Wb!bVEqB^S( zB$c8h0VCWYlxA>#6#78cH@^u7P}o9I=(ImgISu0nx=2)4izvOVmlO!#Wg(P|M&+SH zfEwc+DBhD1uzKAJ#+M!_jb3yMUOp4b#PPfwbCAd23@cOUY7MYag2{eACx1T`BX;TX z8pv2Mg|!CB6MpZKW8gN75IDd^cTOW6lNAqGi|<0sEqhaL7Jq)r_Rp$Vp=}R5sKojX zrZP_h#e1M%M!YHGNAtR&(l%oW<&t$9_cM0&BrURS@1UQs#t7c+{0eO z@NcM>fnp>9jV7-llXf0NP{3iW2$na^523(kBBf^0Vj;qCxQPQ3Hk23CV)Q<0K)FAb z`49M?{*4hFwu&?owS`C?Kz%C6+5Ghvj%^l6gd*0p%+T5V%wYX>{c{~s zP17Q3RCg^0)dxJNL*FVx#8!ahqnKPog%Nq{X-3s6&6SsH#~GK#Avup2U6)7*;jrhw z7Gch(!mHTE!bITUBnSfLyaQw6!MbOF?`F=okk>0I6F4%KBg$H?hM_Qalkd%|z8x*` zf+Q_2ymB32oce}iqyk`~D{?$woA>8TcX=jCR{(c1EjFQ@8%CQZ0hrdB#Jx-5;U*QT z3HNJLYdWiOPiiOvtZ8{#EW7lA!~W{xY%l3Vqm?^5eW?~Tsy^KMK;pvJ`?MoZ&?{!| zffk(gLY{PY$FKNDM?bHvH3C9nBh95BD1YDP0&%*lHU*LsNw_>rqXRL`ehm9J@pcd0 z>VB=q??uXMQ`cB`k!J3hC0A**fiGvYmtG(}CO?^Xl9-$2qN)PSr4rQH4G(Yk$CG|F z*B|3$($z%p)-`vvz9GvVw^s0Bw!C+J24JvGW|b-#$mAx582v7&(+bzVU$P~b(bt{ObpA(A*oqe>1&SnawPAam9&^yOiagDM!#JbMNO}fS(JUkBaTHFcI zC3INFg%;zYBL%SBmDu3<)Q>(1i#}9C<51eK)IH0OmX#EC*Nke?X_Dvgm{k;~anP}H z3j-wmxpIx8r-D!Jj zy31U&^_YI-;6t0o{~*v0!cYlAclHjH-cw>UVQK$%T9S5tgVV`h7$2C2~u8P03xSy`MJ)XIT)Hg9GUnlwT}g zbU(wssBELg2M!KDKr=9j*xR_6!Zq^dOBuBlP?JuGguS%ROyaUki7t7`vFuGMraw04 z`Zmjj8aS#i8Z4-x0zu3P{?}lxMbp3DqosD2ScOu(T9Y}+o+fR27mugE^cB~PE9rXt zmrIXM(r@+Eh_ z*W%6GjFYu)w+FnLgQnPZsRgSW^lYR-ZD9QyB&EGn91Prr?Un^xP>6LYch9n|C6k32 zFFZ8eg137}h?8)L?{OOT*-0)0i_8Y;ger@ouUT~* zsa8~Tgk}x>UP!}6ZTKc8Z{orx`jkdCidcS+-GrrdQnc*XtH83X{V{jk8da}d8WNp* z=>8}t-dznCsYlO&mF#kX#s0OLIUx>^JZ8+LgN$mI_XIBcWGy}NeW*yWv5?*EXQ}wV?U7t*XhJfmaOxk z9B=!tJ0TMM6x*eZ8sV-|Y$VJWHYZFlv_R~YV~l1fLjoQmdlcNIzK zOD|IcmkgmngO%>3d{URr$U7C9TQg)~Myj3bX7_p+DT7vb>En%ANrJr3@5k(CM(PB} z-@x+x*3Lpcqu*Uuj&ha30{l$@Jjw-ce|Z{Dn;)dq8mPI)+R_WpVq#KWwa9qC4ln_} zM||xkOBMy5JPz94%Kcl7)N;s8G^w9xje&Rc3WIi;{Ek#y4>NDy(yXsk%px@6?t>c| zyAN3n^Hgbahbc0dG!#3&8a4LGh1XEoBXMdL-!>+^!C;B$vbH|$7J34y(MggkzPyG# zY^iA{2*8lE*Utn^m9<#Cc~7KAJMXpZRYup!%yr)qevLGlMQ#{6e+Y=*XU28h?=VlRRi=Rfdf z$-$OT2ArD1K17Z?h&!zm2m^avCOKPD>XkB$0L(MP^muYKJELMsK1qCgn?mRsiS89{ zKN@4r2$Z+OspGL1FKidi&g`o>@Y5f||5ur4(ab1eZ<+qv%Ok+2a@A}p&akNZ$D|5Y zUaI>2A6WO}snDU7*5QE|`54@w*e9AetK}&IeI)TqxGvP{A>$S9Cospk;EvepI+=wW zE9&!(30XKaVl=1grQID(mwg=$s@!F|WtfHJ z1Ar=?k9;~B=OMH-v2xjPx+K-gycHs*+T`14=T54=(%O2 z&w9yVtwapmPg9N?)Ay38X+EiL&-!EXb?7{E@nD?H(~j=zH=$(YA1<;L+j`~G+^}r0 z)p1S4gnZ#W6ujqU?K9{=E<1$T72D)WCCij`cLkv))5|dFFatuHJN9z6zW_@+O58YN z%ko0Da&zhuM2mdv^LU+4O3MS#*?1;cdLB zfqT)=uZavQpC$8a=0Aig^z0i+XOKrb zN$x9zBTXtEK^e)qAJ(3MSAbh+i?5E(=8Xr^Tb<9oJF`nz1_aRBe4odK;#p=sRsZEZ z_l)NmoeGd@x=lLn!xhb_`EWF3<=`QTH?2AeesYts^pEXZ%=^#-mbnad*cUz;G7cUWJ7Vrk~_p8biV2 z#T8Y=?P!|?=jB0fb?;|A%LBigB1uTbaiOszN~(%Wcb5B=VFTY{mG95PNCuRv5>asH zu?4GpBEM1g4AWrLx&YLeO!tILap+!yENVeR>N~EBM#TeVf7&i;qkQzqZHZC$x> zj!yoV`{c2ajs&m+8uZvBDe>1)2Lr@t##TO4_6cId33V)ka{&o8(M8aBV5c+e*ZhN? z%F)3YYnu^{T2gaEli`}rubk3u? zKFSaQw_l3NoCL&giEEmEIwj(RbTfP(UbhW7*0!nza*j^00iOk;ZfH#dVLh6KuA+%F zKaDq3UE*cJuedux+6>M{OWvfvWS)U@ACmMecOIp38QBN-7|l_XC2dI=d9kK~QT4>o z*a4;ZYBBb%gM5-86?^pr$J8)+w36*d#}7A&#H?zkB{SmxE|&Tzjsy6=8y*_S4H&mY zM^bgT{5(BDS-zO1Dy;T@;&L3zmqD9T8dE6595 zv3!eEq3tvReqs-ky;h|98SW)d)q$MI=u@tuLGcc5_+xw-xuMAhb?M2^=$$_%%7out z@1sY+w1ukZ_CDDJhjc+Ry^KEo@ZR(;;x9zq4OP<ciaiVG%#sV1BsK3% z2CNPnYy7hD(G0*mm#gwzpInl!vU^n3Ex4!-8 z=3DfV*d?rJ{3u0G-I!`67uM}RviK`o{Uk{LB9UO6rsXAe;3dn8?G{-qI4gE~+ben^*^vuLr<2UCDE6i%$E_lUNEuqYSr=4Je z`eZkL<-p%KmvMltTSoR{NI5Qg;}Kt{$>iwWI=O&7w0~IJMtTx#_#Ntlf$YWmx&-Gh zqutBQ{uuq$yx7%;CwEZ9=4hkd>`A$|S_<^DUttSzJ|6GjA{T12=5|?=1Y`xoXoK46 z?aQ=*0XOvbt$~xmyyYJ7n9Ua)&eqG^mh0C_NPi=`7^j(CnI1y$iZxIJG3cJuST3G zTWGmCmJkPOC}nZdkl`q&LP8x{u3*40y*VHS5xYp?asjs3I&0D=^eeqH{;{tV<8%-0 zTwPM!2klEM$OTgkC#kK#?Lju6>QK(&%o*o<27AGw_v2+b8T=^{CErGfOiWu=zKWrpSskjQBa@asxz=y8+z8**~s zq0>xM#`7Lt+mpLs{^JeYwy@IglHl#$vE}G7p#n1NKs41Uxj>eUu0kh%LIE}HWMX-IA~ z45@cMT^M-JxG@{<$NW)r=ql^U3)`If?tgl+xU*vlWODrFv6+FT#Av~RR`Qs6D#59l z>cXoB0Zh<#ZvNvHfhoo|zlndQ?%;>frt7vaeDL$`p{%;PS-B&}WZZflj|*IRL>s>b z9$R?krrAp~g_mEXa~|zF5w{zP{7vOBM6jD*oQmKvg_m7y6=@4gIc*ssfOkUHxdf=B z`mpeI?hU%W)G0Q`9}h$s}i>FMJqpk^alNb1_*7EI*2HEIlZt}|`YcTM2jXDqpZy46t`2;Y_CkhFcdt)?mJ?_H#^sYb<*z@V zv1*~4$RszvI;)JnV4J{aG8LB_{d%;-|2NbZhBk5UtP~Z#_VM&a15S@X z)xT0=yZ1a(@R;aJU2<=sh$Autcd5#+|7SPhS=3dxjaT^*W#X*Dc(22&Mvq${lJN_Z z(pzXlZ1H`1AWNYnm+^if6-$`pWb!xI2U3F!o-#Ndc5PR7fSZ)%yTkj3KfPV<{VQeR zl(rnlHd!Zhl`j^B-e9^2^6O#{oK5;Gl;Z)I8?3mOS&Cqk#m6c9<;1~%r6WAbu3aWm zDhzKnCo`7g^$4W?U5zV)vx`^N&{fu?>P2HU9xCbIV`>cN0HJlP`i}wlSnQYh|pa|lDIIFOyC-7bmA(-O-8@VDt3*eX5{a1KoV9M zE>e9?JZvWkn*}*f_~^~s#z@|-JQw_fm3W)T%tTHquPJ=?8e4I8!DZZD$%F^-z^)EA z4*aQU5#)()-xQ}SAGiq>F&0OaKUN|cw~(eU9b9}TPgHgdt-^l|`uWGvjE(UT{lItj zBPQpXKQI2&anoxGi3ioA8wP84pJoK;?FUB`j3BJ<@viS~pr z*II898?%^ds{aY`|8mCv>=;;l?$VV;_hCwnxz3tSbxK$6^}!SImxfpLcswZOI zXkg>|&G_es`!8|g+2KAt)H4+^SZ$~&BX^JAwha@^K;A2eg1Vl``DAY!<7LjE$=4Wk z-^#D`?6=bZFC)5tX^V+bJ08MF?O9>rBH0ZBiN4Jp`OAt3W#z9ff)Kp-#KC*s$ zxv+&-b&eCdSKQ?z^(Zk0;ESKPxsi`LrZSF{ULK#Pw}$up{DG0M1?=Od=j@~_jS$+y3kk`Lfbuwu zw_EvMwd})+^>|>D_{92Ym#UzhFj=|gef5kja}p98hQbHV&qOOYQBz4yA_v7xFxKoM z7xcT+I&QS%;{7aZhqIaNH}XU_J2e>J*LfVw+`*!p+j?rMhrjP}qBm5a7R(zyv|_z`J;BnCy5_ z?pECwlH3FXlqk!Em5+jjr(V}`?d6PX4VZqj*H5=2F#9##7?(?2zeS6vqfF{N!!Tb) z``-dE8}kX()%2L4&=5m~BL-)ufA(ah>ozRnxm9k8w8W2{uq4bc{}RTCd<+7R<$CU4 z17;Xq)c#2+|CK1Pb27R>y^i>#x*9MJ()8S{7rXbD1YX{R$~6lbD$chX((Q3%rN!Ka z=96)wt(}hAf)VM z3c%*72i4b59Hr`_H|IU4x9&rFKi)s|jV6Xx%*SFTTvl6;u15e{2Yk*Fmxad=So9)} zfXqTX2JpOqW(J_S#^A_1@N++~NwlxDV6t0_b93zsHN*wpB>K_Ys4oB0GZPE5e1P$y zKPyr7AJr5hphu(JIlE6Sw51rGZ!MVbYRu5svBOwzS93tApnuwVm>346zC*d|2v+=+ zBeqI;N3L)i!en)KpD6Il_r!dQy5tcVn);*L%GN~7Mp)*pWN#E+)Bw_99)`J!>rY^^G$;Bgs`=a9WDN#4e0mGU=j8 zYM9Znvs1?`)PS`l(U-|+$j2aGyb+=2a;m1ffj%MgXskxCVK<*#K!`5;7w81CcC#_A zK7KQz1A+3WsYJ{p1N)xP;ys!3FWUY@sG)}gW8@nl8{#Kx%;+PTM~m+;dDq~a++JUn z%<2X!e>>k&EB{R}br-!gda{1P1)c55{>zx5Nxsf_%;0jj>f{jH1WB$0zm`Q*X;J*Nqx&EPql|+G1!{(9= zf-tfdxmP+uqJYZ0;;1weL(G*_gVFExu6XtT36N{h>G%uZxAIcNi?ZTzQA_XQZUM9g z$>$&G`s08YrbEL1%fbVf<CeNOiwn~L*1TZcr&U8LA-E&Q z&y@(Z%gjbK#ohrmAwZz7PT%DTUsvzZiM2{Gu?WzC@GYQT9t<8MFI8If8D?87&xek3 zQ9~DBP7Ry~wo>S%lrkCPtNkNUi+*y5%`cwEtnVJz{9*!)-E_e|9u_CF+9 zgNKGEI!sdSc$!G+G1Jlh_4h&Qm8upl<<(29md~G16PDs~b!P5t za8A>P8a$Yu5-#ZMCn+thh;8%_DSK8dI=bm|%BteM!#8lv-(i~_LhBWiBePrI1PPfh zYm5zDQ?JzA%PqTSO|>D^erqSQ_tq`YNLv~F?r(UUm>WM6Wp6@1=Er;Ry8)J0uXGAe z8gzgA)g6+3%OLt{au-_?Q$~Y!G+)$*TKj6}vl1pY=8$O52Z`Fst%g3rFO;4p&S&FE zAFb!;q>tXp|9sy1E#*~7)&LJTnzc$C^X2P^;+a#v5=Hp15rlGSc1}N<+o$b;)C+YopFWWj3KA+Z%_9TaeuNO7%>nuS)_eh1tn|TR;3IGGK^5c1sK* z3$-zd(uLlLW-HB#*K5h+x*w!SYiF&5&qIv(oV@8jFqeDB)IpKVwlb5Yh8S;JxIEdi zu(>`N-Ohsuw9jf6n*X&sxdOAU;Sbg_T}?%BZz)@krzDmSJ|y2+Y?zY=jd2%&UDC1* zy=p~r@im<$%mwE>*^@b4Cv}IDmBnsmFMBV(4=nG?0e?noG$@`8f2-m`Wgudmt)B~V$%)|Oyy z5Q+`x=De0%6thbnI$MeZ6HE^nsCf>>&Zexg)3K2vzg2?^e{#Xy2dtG_+B&5Dr+=<) z_l=q@IP%-Tpc3K>gW>X%1TnP>qSuqe5lu_D}5gkYS=v0C@UKv$;rs zy$(^&r{BSKOFi}HG)yLLY2JNkcXbM)#};R zjBiG<+kNe0nEbmN?5VUX>~c?+=hrAF_7Q@iT)Ij==Yuti$SrYiCQDFd$Mb2klcE?A z4OY@lOJww``hoh8A&($)G^^IGVCyt1cFuRf4z5?8PxP*!B%iWV1HvC1+$trgv-#8V zqQD3%6xoJwC!N)}?&o^AGl&$(xb>CtOa8Mco2f8_m6oE8B4b=G8peOD+F;D`L5JzCT|3>&*pSaHT>Z-e z8Q`xY*tN%ktQ_~Bbr$6qBx`FTYH(kl6HXQ^;IttGNmI+#x4V&Q61CkeZe7KouXo1UQJ6@Trny&9 z+pGiMhW$>rSCA=W@uoQbZMhC*>~vkgYcZ$n?ut;Aw5E&mx)d_M!%eRxUC{I3F53mH z!rEiP$jLb*dnuxg}ZB2>Afjrcg`=nlyJo`}q} zDS4UDjQ3`DvA0L-X$Nvkfy!S+Yb}1_#Yvh;SFz|6Z`1DP=^HqXfA{v=qv)*Wu-iD# z4MpvI7sEvF(BXbvs`l_*EEC@1aRY<+F)Dj(8eRj;jx-?q$oyqpWkWIm#I?rCck%NX z1@LR7#|z)ZW@_L!U-y&8LQT8v8|qE7J7T#0)7wify!=hO=EVY+GthaT_9Z&U?6EEL zh+p&f;Z8FBh6I(E&)irI{N8msu)m{QiSG1Prj~V}u51X6Nka9^HrvB0-MIgWYQIhdtGzrFXP?%Up<(;$#GD zV^9X?u&w#XhAuD~Wo;`4QF@}aX44w7%iX9P71lVQci-f`2}_Dw>IMlOIctDux$g^~lKHqd-8Am<)|mO>_L!WGS);Ka<2$8#1DxBk zF$8z}<4oV&hgqMddw)Tw)@U8gc}N?#J>j?iEE-Q8U9P3pa%`)$7IVJ(Vku--9eM2e zJ$9|nNbSHG(gU#Wd`H#|E#c#Co6Rj;@8pdo`Pt*GW4utsHuR&5O2+!Ak?Q(Sy8gOe zy3yQ_c&^~ws1p;4uL)0)f5M74N6PEVt4j@EMtZtvfY|UMGXjlTRlkHh%`~Eo10CwI z-(+wK?!w)d56SB2HUsRklT|#UC8(~Kyy%-tp3j%j7YKO36BUDEjpe9~MGDT#eA6ta z=~-iTD;d>Ye?7algn+wm9p3X%h&cW6;Etu?v!y|qZw+^gifg5i%<;|5Jim5#bN?Xp zwycP+LuSMpg=20enm<*d<$Itl*Ti{qvt>h=nB1e|XQ+B8yYk&~@P;Bg2z0x~7#V+T z?=Jh>Vy#bq{wC-roxs}TdRO?4^ZH}ol>r@)|LD9GWHpnpx8JOri3W5SGHj-E6Fr0n z$$Pz6J(@LG7rQ{c%Vw3Mm(SJve(6(qW;72_jndtL4fHiX4RN=%uqAJ7*lZ%VJ6$(= zBwcY|>TQV_dsA#|Yhb$u?V#N)Wo98W?(3j>nY9v4J6Y-RyX){V%tl{z5ohufi86+U z5xX+m23Y>E*@L{LCZj5P8UdYLPs2(T4C+h~^pm3yOjLGL!UgeieNpws=rQ8+x6kK+ z_eks!dX)`x^$4rnwwukGu{}Q-K!-|MlkNuYHTlwIliU>3N%DmPE+e(kFO72HcW-`{ zCe1Ui)wa>OPpfZ>2bvjJEm`{^ti@7;m9N{Id;|OZLl$ZIr$KMy(B8AH_D7CDapE2R z+}Dpl{%+;MqGOBv;oy)qM9#9Vr!cRGcxSo@(r6e@)=TlrJ%mCZ;o4w#gwMfh+>Cy_EcsgQU}SLhCH&> zMIuSP5JV2GaQD^1jG8_(_z#_!qcmYsx}9%)SOoHmfdI$o`2HxQ1M%)D8bNd9Y!+ko zVde40jeRL(J2WvSSG7gX`_(N2WX;SAO>N*rSX``(s-Dcq#=6D)UWysePnh;;%h~Ty zPey$>{CO|XE9Ub|%Hre51m*okivZe-#Fvl+V~^F0H1L{b3`Fw^N}EtgL)pjmStpn# zxPQ8R2kK*)N4`T!S5G#+?=AmAcL~P0q(n6lDTRQF|9Usdpq!O}G^;9jOlt$wF|8wb z#{7%1@qsdF)2kwSs?L38r(e7^o{veRxh)|fO!s~DxJo+$S7F{Q*`!t;uazFanhp-u z5SGh0tLc7Uxk;o8!4E53$296oI*O%`gBb_n4+11~WiF?R6wPanG_hFrwa@+jlLZpk z(-z(Ttq5^JUtWt)}olE~Br4T!9>+Xl8x#agY!*lCNGGj}QD-8u~tks;7rMx$HpZ zQ6LDXy2FnQuFTOX#FBtaf@~nP0rHa|7BrC5E$oYblgaqi8*<#isKLQlljerdHj z*Ti@r_~Kx&H-pySNqP0LKnVWr9%APzVv!Xa8!6;d_m^$>8zYqFWlM45FP3bbt$$f| zc^uOu_RTeONqIB=0g0MxBI9ieYE<~F2aO|yO+{1`^VG?ke|-wGwbz+=m^~=W8@S%E z$qDBXKGmK<&tk+ty>UZkHZ*qAY;s5+<7C>%Aq`(P8v>lL?)7qb9NZjPNvMmIF|P9i zDv36yS_n2pdV_qQWHt{O6PnB2=x$SR;`>D|Y%d<(o%)2IZNIDZlxf2!-BfN`;KvgD zuqvyJ-S_C-I^K3L3xw8FI24~Q72niL3R!w<%(bDgJG|0Xv}CB#CFxOAx-?t@3d(L?mX!l%{E?Tfz0NgYSi@tWh`pz zcBVcWfTE7xxl`3?Lu{2)QYEnUGDgu&*uEf2P((FlXwD|5`MYuU;0Y5J9+xogu(-^z zvYn_~#&RXC3L}LFL{S+A7fgiA!N;eZ_TC0?my zBt?V53!XWz(v7Dw78AkAU`vTgI|=dJ=9hx5V;6YeB85Zwv!siyv~n(uM=)kb$>AOn zUA8Z*UTOE?&!26vFABx8@teKuoliPvruLs%3zhmg7z*#(@&{b$E#V^cuI1et@semA zJz<(XrXX4~IQ$XSc8X2T~;ui!cSVoJY6ClbJ72`X1c zk=nTiPrs5hY#M*CTTv>n2D_@>_++nf-W-WAEPAvSsr6Cxi5e`^`jzvvA)RR;WF+&Y zVe#(~IJV#Z=5Wv<%1J2CaW>Up1Ur3w2G8#w4uojz3(r?fE=-ZnbY)!`0Lu9>!*|IW z+Q@%5Fm6!I) zeY2|I%mIRV6Z3;g` zHoTRIq1BA11sp4WyEHPi^OvN5>mF>SG zuYU_}>V9p^qr*(Mb{HzNA&Z>#4({dh-CWu3RcUpn>YJMgkwPl9EZ^}X_FQjre1fU- z2alRi2pd7gi{0;Hx9JRtcR4>bS5Q@WK^o7thyci@Tkyk9%6IidjjJTp8@l+1%}4W% zJU>T6jy9UMP6FLE;sLCwKUwiky~Ud*-SAK0Y0asBe5C7hl(DZi)Lw<*G+sE1r_OE) zi&ysMlk_#K1kQjxTLL z!+$n6+93`X&wR;$_L4%*Wt}`$I^Kgv&##SA{hTaY8Vu+8X?ot)bl&SU+t^MWEs=O} zG1_##<(Fo_Zt|DRW8Bkz?DnbEpP+3omk;MPCv`tn0Os5Iz0D`u2I@a=g*f2CvHE|T z?1G1L;UvB zzqH9~hz!qVlhTM+AgKQh=(D=L;Sq)O`mxM_?aK#vMa5#9D(o##)V$Xw@}G^d!l#eT znqA=8|4E<*k}<@-NZNA@gJlB z!pwTb3mph<)mbgbsc)|GA36aZc7XcR@c**mN^)SxdvL7wKifb|0*?-@V!2;oH zjwcA5nNQ6Q@BWeis9iKpy7aAo3#c|e3e5MHa6nshsp*A>{vi<1LQ8+F`hVBJ!Ghnr zcFm%sJ-QL8GTrWz4WV0W-oi;w{tMZ;lr0Ltir)My8zB?{;Qln+e`!yeG(6`Yt(4dJ zm$?1EHY7_QK{$1=hFkv>Ir-l&xl8vTfnNk0upbtrhMqlKU8GF`%q= z5LtiJGAHAA4Wh~QXZP>!8m&Gqc%P{$H!!?bqWb<(+2)xB)8>!lx9S8&R=Hl&`q105 zzb}o+em`a6Z9wBV5qAZ4BYoye!do;T`aahBMB?BLw5Hz1ux41=9{I;aHKCCdWg*+Ztv`we=FQw zK(HXEj682f>R@@ZH2kscr>~!j0)+`|xK_bX&0WXeT&PTE_6%T9PH= zZldq&Il*F^J9(e=y@rdxll?8b$4au7E`g&K(rj=qOzpF9==+qAmpwt<%#}{YH$=41 zZnk2_pPGkWPV}c8e5y=8(RhSsbFR>T>35urn5kpXU#n^R&0Y-0+IY!B?h$0g_7MF} zhtMI$4kA=isW06N6j+XbC4d02oce`~>OLn_=HCun-9k@-nvwN;KQR6j2 zuTTGq76XQyAhXwmC+Tb(Iq8GKq4y!OCabUDtTM$VPwKQdvo*=GG_U-gLh^-H{sxKW zvGq@r@1I`AAiv|lA+;laX7L~+(^52Uw=`TdYK+4+R!cNL2lsCfIb01(95Ne>3GO!f z@^>tcEKYQ1*DY4&)P zdrTu%a$bgm&kc~y<7V2~4hbHgqaeG8{zZ`Sb%?n@(|ifB6qN=-NSMBif_ zwCiDW$?@K~15;`Aflhu^>q}dD0?Cqwv`XiPt(0sE#|JPA6A$UE*;gNJk8vdM3Wt_` z7h|w(lQ8w(aq5kz%Aj$-Av`3Sbs3_(JXq3C=`&jh0mm*8WH!6~?IT8D%Ri|$$1i@O z&~9oH>esI%GVDwHwO6x69`Yl%e)lq&Z790|v(z_UprdiHpiI6tUl z66Z`IyoQPM)m*=e$RSCq@J{g{wnd|6{gas*MBlpWg134(*(-4_B#{Yg2>12EZ#{i; zi292!+0As-j6We*b(aS4pvl^+>UoD*(bD3xxvAymy^w^RJW95pL+{Wn{Hr6|sJPh( z_0Gp-?Bx5Zoy)>}>>F^Zf&Dv9)Yj%snsoOqEf$rFYR%4DL_$YK4u4X*;vG|aq-p!E z?|4ws2@g$uk{)L&x0q~r;F2{tx%Yss|N73+oy(5&<}CfOqLLo$Bhz?BiBRlgDXNxb zU2lM@Nbp?i{i9d3^BlGG;>EwD0jK6Lc;(={GY9M^2>@vWK<~h&Po^71KJ4KblccHv zgxnJLZh)T%nl;N&O@1Q!Rp<2=h--RAWo7%z4}R?1!%g7cXXsP2u2R)j@1Qpfz@&Bs zv=ve9l$xL}OVv_k^sff&$3xNZ+kgW#XIyQ91i3BaLmX+~faA~LPJD?3aQDBN_W{n= z43LtceFyji+nk@Ix9`GpJSxF147QH56@UMv#y+Nm!X=8BGm&5?9LU?YPtx6zNa-^^ z&#ty66xeBwNBEi_Ap38?H0|0w*)kV}O4-dN1=SyP7ifg9eHe_aBQXkx=rk-n=byf| z4v)JDcUNgllin5-t0DT92|j69w0Ina?OS;)h16aA_lVWU6wpd1RjK<~jV}>*W3bzK z-qOgQuRWcq-l7Be2^enf)vmB*Fa7>9u`#9$?nq zB|=n3*Bvf20%@~D3k@EVVcZ9#sULQxKQ&X&?|meK&?e6~vnVRQev3Z?@tyFIt~izdA2(K$DB$K{_mYbA+pacy)YY+a; z%30RAT9e9AJ<0;Fsru(C5np~E_N7@_^p<}4^gG@D@r3>dDLNl1EF@CqiII2dc(k@&$FKX1TF}RJtN?= zuDw{h)W|q6kqx_b)y#16VxPXk%fiv)K1Z$bF84VVp|{|m-ucU=DkGmx?Z=$dX%!_Z zt}LZzN*O{Zn=3{v1 z+7rAad^qiy@rvq4(OTlV`-5f{@G*|sk^5f8Tgk5)z&Ml&YMWAz)0(psV)uD<#wm?$ zC*CH5%_m)zz3>7zI%Q*yO1913p}q0w#bT|EkhUw&#~ONRM69|`M9HE3G~tCq36b;l z(}hz>lziFAP&AVPGB;UY{C?eca7Pj1Aw~c+Fi75tcr>c`$Fsb~SnaMGPfJ!ul6lR`R-)3qF41>HKr&ser{H-=C)$XYcdHa@xh`=*C6 z@RGrfm3Q6_w)*&Q`bN1C=VOZRPOWg)^o`YK@F-1$lcZ-6Qa44>=D01|z)=q~ zz8rkH>W0N=#G}ObF`<`#oGn%$#(0S)GsnkcL^>|2%(A?_N^_`-ZQn$odfN^i`{qJ- zJTUodB#vFc!d)2p7yufWS8^qh3p5{7GO}?Ym(xU~+=RO}Obp8MQOY;vFnQtnft(+fbZZ#obW=z>q4@%H$WL{_1A*b}f$7t#E zvi2``gknHDj6u@YL?LIdv`h21_?>>N2Q#VZ>MQo3lNv)ciYnT^Il+Z5o_owEadKQ@n zbo)=Vn%sVC#R~{B*p+c$I&{pmPnv}V+3X`%R>5+joZ4e9w)l&;6#5@=L|tS@la%_n zlYO?dP<-D!Vg_7|l>i^?+Dr@q%jKT*@_8sC+pEEgTps5beIz<6!RmKA{$BQyhNv`h zH=8ekUHU>CfxaZ)b(q7A~1?*nfuNR4k+>OPN=>LPgw~mTq+xh@I1lNQB39f#FI7%*XZ;OR#%XpV>qvWk zkTw)qs7?+Mr+l>eJZ?KW^NynucMmY_TM?Y%1TGxix*3VPj8%93leAQ8g^`y|#YB8! zA#vlXyaFtrIs^ACH#5Ik5GL*_90#E*_5At?rq8m)nZHyUh8cpWAd`pNH00zy;^^DgNTqS!t2yv*#Bu&>b ze^#un0IjG9oTp6B$wyG`{bae|f<8=&sxp=f6rv^1^L^M<{AqNNi;mH{V;k2ntU_%v zLWnZFEMJ&A*w2bC^R!qMA*9%4IxHbg=soEuEg%h01tD=L7TdSDS2FI^$k8KwizCOfBx z$@h23(*C}dS{MKkKMLc1AQUL={3Cg)*}%;=OsYct5p1Gaf088^Z#1nbz(1-PX+4=n zq;38zg>Te~giI;Pkie`+JK79ag-wh;Xi{cyl3{-;UOj}XCWJ4^CS3TZM8K8*O>?<8MnkbbDs|;A@(t;7OMp;#On%iAFGfy z_wD7;?Rw@Pzt$`eCmQV-?g#6dRuOiF;{8wS|RU@qd1ysRG!%Tq~ zDMHY|3LJlTP6pER)AUrNme;|9ETEmF4D?5!Gn7B}HFq4p`z>`_80!xi=uXG^9#7#t z=!0HCD?ErNO^$gS5pb-ypT`v{7>3-agf0=?{Sf$)2xKK4MxPBz5hW)r6p0(5GoM$< z+?i+I4f#3H8t}?)SKuVD=~9a6gsx4u@FlAGdd#rlUxyf|-`M)1`(=-zel%1LF@-Z) z?W8~&XjJm5z%*IR&2)(K9YG=w&1nd=dqZd8U&+*`O6;*kAh*o(fy z^yL|-fTMJI!RukSE`#m}4ZCV*%jBr*ZwTi#ZYX#!&svfxMF?Iu7)@aw<)IV*>7BR2 zu=m6PDcw|qdrXBI_~KF?%Cs{TK;?V^<(wuliZ9?9Sn@^Ch!r%QGW3l@zo#~k;9In~ zOUH)|KiXw?exbW`Cl=zhT94q2m~lkIQ!-2{d$7^D1jJpvH$14lwx+m*0ey`3?#=<1 z<$f@9J>|#HgD-mV3#>GqnfHSc{@BMrZRu_X_B3r0gLg?BY6W~oUMGobJDk^Aojl7I zJogOr<6H~k&v%aLNVY3P*>R|Is~$Y4N1uyP=D!gh2~pwJb+fv>fVIfq7Eyiv@X_;h zV-TpzZ&(T*6n!H`g$oioLU{P-_rK(bd&V!IBTzoq|5$Cz`dhWJHZwcx!@2VB-K|+3 z+GHy;iaOfai`cnqKlF;@02)hka8_eJaxgk zt)-g3ZW$zX6TJ*_z#(`a`$A@|R&pWyGQ!(o`?ab{d|CG!#(+m)%o$x(-6)l)woLEa zK=u%a(@VewGgWzE#c{2gKK@Q>i`ehbBw_6xbvR2;%S@WORN^FMkIu_`UG!oKIU7Tc zxrx-a#(rx(wfit%b4J}~<;S@nK*x z){pfh>!wS=uMenD? zPviujTKKqceTxs3Z&4CUZvPYPU>rm}j;n@hCNY zei|J`7)N=RA{|ts_nhhUv-@)>PR*RJ4v$n*aVmB3k4C+Sl%e0r+D(vr1dxs^uOTF1mrKivgQo#bG?%@9Jx`yuW= zhglS+ryzaFlDhRON{fYVGVc3O4JqErH-Eeuw}h9*M-^9?yfThL``?y5hr54d>+DAv zXpl#KP*JY{X$q#Z7n}KA4=l~3ExGdh-4XD+@Yf~9^!P@0(1b4@(1!YN(BB(LY=WoT zBKx_}F4jqNI`OR6ax@fErQ{`i-hgkv1}8j0iXA0Ny4n_fDni#%0WrTHcutG7Z;ytDJ8pdRN`>DNj#f!RKt~y>sU2&-$jc&mJ#UUIr zqPa5`_FOh($4Z3K{QKr2{43^Q-Nh$f#o&rHA(O-*0vnD@X|7l!jp1ss%SI17&qA#2 zOcEYFj(w6Cv&zVSOy*+hDVbU7I48{Je`83ns zIGa&>XdESb&|f3$togX{C0+9D*!488vOXopg=zV>QLkNIUX|jY*&d4GWj!d2ANnW<7PfF=P1^ni6E+cUaPq9rGw&q^Up6EErW2Xxa_y?d-?Clv>oTZ?RjFQnMatSjlfLsX28&z z8%|o5UB<<7u!Y?y2i>?EoyQ~G3cq=T)A~(QLsX4k98R*CIkvupbRvd2S%g?r9f3SC z=irkW46>DR;&#GNV)c;aw##<)&#z`qr!%o1Vg#qCO;Xpm`Q_HOCZp{QLg!AMu;^{{8m zU_ynIQ=`2M*#TZnpY88C@kCg6PCNl|@F$ryNAdBrR#I0&k+30<))q-IL6}E119>P| z?sVq@a|*c$QpEyjuw^?uJvga#2Fw8nzD}?6hWtr!tL+Toso~>y1Do`OUlDE)4Zt+K zC*kDUKC@>53zLV|-sWLEL5gNXT6<(j^|FRH?NnQ^2i=`bV8f<_*iufhc0OtUotku< z#^ceE$kNI2FDw)puIJzTT`uu(*a_(ja0eXGt=K60z7n-3m?EaWPL)VB@L9^Vcr5$* zMV{)5lt(Ts{Okz%Bb#tF%u3JEuB_`P7@HiVDcm1>Ujgse7r?P{YJtC*C(x!R+%z}O z1#=hjwJ4X7N+uD<*Ef(Ayz2T&=uzNp)llg*WZsE{Nh*0-^~R&VCLfgz40O$TuB_EF zi=_+0zM@=({bJk5;x&cJI~IgH`>lBX!H5+YuTYy*$yT9Db@x6;&07LidCBg;xB%{- zg%$74#?ID6OWnX+hrH?MsLzYqp)GJG&>yG0^SAO#yOx$lqI0FoB{RBG_s-VW`14gp zPbB8OJ`4v3av=Iv44uW?Ia&&Z`Bu}aOJ3xN9W>l?W<)J!P@Wdb!zW$ z2rilH%vS{C?(VPUb`DvYvmLa|)V_0LWMNx|d5_3Qd)ed|@NXEu>ezdQ41VflO7EKH zq>;d)T*RdO^v5)-Ih^IeH`x_UVjF}XkVGB)4oy#_1hs;P7W39p4KA|{`EpQNUvv8*tj~{o4PosZ#$arQBRJdHIjADQ^P7G#Fnwz&M}o{uZaveTMY4;;?JR1thL!Sriug1V2sAi z5#x?3m5(p_VcCs|z&z21803t)cQK|MVmawLFBN!vN}Ah#?4#xGRlYb?jk`6b z*dRIJWu|nNMNru%Ir8;0Iqvy1VdSe1kr8ad>0D3P6lbp7@@ZKlEZ|HSu1)6znBHXB z8@!u7m+S&!MI9?3DQ zcdLy*hZ)JP+Heb+M{&*RGlNI5^Zg7Dk^;6u96o|P-Im@U>tP7BNx!xy0DB}SGiJ`= zZ&lTBCiJJU(RRu@^r@it6@_na=m9N(CMeo@Sf9AA-inB*DL*dZNJCn|3je%>XSOh0 zrPDtO!VBU0LdNak$KO8oDN4fnIeBMTz?{=oeHoQ5{~-Cee)%Yq+nl~UCicEu^)nGm z4TA1#vQ5%V)ieZb{Z)eWPL+NOb@-1C=$tuwPX|uqmr#cs7!v9k8-o&JA6vy}J0kM5 z{CJt-@s(1dFuu<|v_7aHsiAO$eW4OpxRoN|Iu&@)qI07M6{gP1_4rkRGrsEXI!!zq zTS7Ro^s8=R^+J!TCtLF5{Lb||GNzo0M>{5Eni8?|ERvqcT|MENK{2@jkG>k_-Zk-c zkPudfsK1EjCJZ{zfitqt{YW~WBfDeqA;Qclv)jF_spLLwvH8hsyN}T6MV?~JyM_aq z73**jlCSGDFp=LinS#&g;@i+I297jHO|@R(H*^XPQ{gEDYDZdE9(-ezZnG&AxxJJ0 z9SZMQ=Vzp~b7s;Od1;RXtLLuZno6cUHmWaaA)=U9l2YYpT1U32Zl5M;rei z_9N6C_@9Xlq?@sZlf?3_SYal|VOo^|)c#dOV0;LJZ5!;GhJ8l4TElx(&M1MrS2;#* z{+i3*>7rorHZ)3kQ}d_V45n;6%CK!yUkq+t7y1~9zg1rd3z$kZ*5$X*X5W6o1U4PH zGNIZp^o5gXO)F|BkJF(`KwfGG8yaYd^TnSiNv@caw=d0~M83x0-SF#w>LV;9i^8mZ zrz?T#hi#y_zbCveeV_^DWub&o<8pm2uNiYF=T$E@2|2T=JgUiSri81LxQTF9T!RWc`t#ZC z!ZjFP95|URCSLT|4z0q)Y2FLez_>tt2K{;m$_fd_@`QUY>jnbd?tnb3G78pG`apk6tWq zLlJ>|Ws%cF)NE)gHI~0;6!z1l7A<=hw2}T}?sz-SZZN@vH~Py`=^fP<5URw0$^VEN zJOs&qM#TU18D&N>6IY8jCdv{b|K%xVHdeO3o>FFEWn*ReztA3?g`4H??a>uNSJm3~ zTZbq=`j0eKA*nQffBejRxc8&pg~>>Gk4X4eCjX29or;cVaT1lF4n=#1p_NmTLS!Av zVMLf^5p{ngj27l(_3(8gSWPwuLwDG*7b6o`!WV=xRdh2|%{#G?QENkHBhFGh65Si; z-5bzj-ZARmQI`MH<6H%#U)LD;k@SN6QGXpj31EB7#`5d%EygJ7>oJHd@Js~o2Z4=1 zrD=Yt^61wYi!ga$uWirkUng&6hap*2+AP?=&PblIu@vqk{{KJwe~Ki%@F*bA&hs|f zM<5dNi>5~j3(B=hhIk;L*BI$zkdSLujIc@lYn#`}@E{>LN#Hfd(S+v4iZk@8_}KZ6 zK#Gqr0d^WA;NiY@m6-s)vjBl!zYPMIJ>w6C|9|_fCPY_Ij^GTFb#)#uS0n|=ih=Z> zfGR}8OgV(uA4r0kDkN`%)=v}s=Cv5?(?_6p@15CLUO^K-M@Wl2gA|qeYj)Xx2n!`4 z17$JAM1tW>9!M)?4#Qo`&Q$y&Qt9baF<1~5<>&|`t3>-V2Mv-ONkJXFDRw6_4Ou`a z=!ae>9fo;(F9CQC|?2Ugh@%@$Iy`KQg|C99%#7ltB| z!GMsTZ2|n51o)E>L>aB3{kS@8`33eEscEfC72ls366VA_u(#paFUku4Mp=qCi*xHL zcIOx02>Q<=pT{;D&6f4YWW``Gm!-g>hVVXp`T`x~`1H3s9CKx)L_O;h?b!tMu_G_Oog|IjL1+MzCEGsCuJMAJ!BVkvKuT(8ViEPOPTGiu3~A zjf@PK?;6=}vczIq7HZae{%)c&JvU??A8K4g;MKOjv)nfqEfFzTj#N9jhYwwAr~w`@ zUj_g7J9T^5;4yD~#w|?}Jdp?&f$H-{NL1VCAJ-OSQ9X9bPp$=m#L+=pI%MP0|RV zn9#Z|ucGU--t0*Sh)Dat5z#San$XI3Z<;YBLtY|LNqUWO60-F8?C0*yRgr=gAIQCR_8Y*mHK{R7Gah*Va9)t=x9IBRmDia_w2QP zGiUm`b&khRz9Z8JzJ1_1yQk$TZUJC{g9cMfCW1XNF#|3TMEo}mG>-6klWs0m5Yc%I zQJKO`!2)h}qAJ*|#k*s}v9zGegMYj`E&%C>^z5Z+~7YCIan^Oi+YPz%HgE ziBu@zWC-ScOY(9E7*3JdkhjzY~xK?H!&{b zkg#pBCP~Feob zWMoWQ*5>&nS=Q2&X(zH1pq~@bVWz%C1};yY5R2ez*JIv2aHPc3Jg8gpRHos#I9>7_ zYO9owl)2JeQj#UjiMd34y9`2S0aj8W(X?ROs&`&{(AD+sVyw=FG^ML_Zch8~9tyQ0 zjrQ54%Xo?r3cW_gL6Q@KW14@|zYUHcXw66fM{cj2FU|xt>V3Bld78V1i;4iEkpRr@ z*;jk6lLWiwg|;E0$|r*&bV+?C+41k}7iB6W&0%QXE~6W$O_>|J8K|*QUqcq3aZbL^ z-}?T%4{q_r9w;E5FK`(o^z*?;dk4*8Gq`zrZrkB5WzNmbRg|uwnXnx#|GGmQTNUqi zI5wY1GPJ<=Ape1`C~xDWFN>DYf(S<)3I@GcW=Jao~uNy zxK>LpUlvSGj1CNFIxz;JH3#=?M;TeN_xY@4&3m4$m`x542J;sF#&D8n`XoyQ4W6tb zgj0OEJ;r}cBk3%L>Vc05-#zSVYBE1&gELV3<7SxG2L0-t2Y8c9R`gi#QldaF(0_m) z<}%vQ(t?#?I_FB$isYhGss=r6sxgQehJ6j{B>YlRHmP-OGSnS>Is0B9IRWgNewRYj zGI-yfU+;+?%$xlCd_oT0br_Q9`=l#}mhE5Zs7u;$caUWx6@mak)s*9l@*cBLlg^_m zy_@UmvIc0?WVx-i_Tp&H7us`F%&e0g_-{gQ_~+(0rH*)B#u1heIN4MykJ7A@G;Ejd zVM&xBuKBt)j$NtC#PcH&MT(H9sZbKLD4W6^&M28aGjlj@5xk*UzOYc$k zBX>TW)lJvtqI0_O%3%m*U93}K4F4LTqZqj;-P%OP1Unu#otLd1975dK6vV3j!va23 zti`IbQI-pfO7bQ6+dA33&JVw!0@K2n^TSSGLvIX_Yq&F;Bax)upa;t5xdk8BRXHD7;$t(Cvri5s_`ni6Z zWufS+ap-BD{`(OK@fD)EF=*NhFjB`~n&_j>>n_X4)u!rS^S?TU=BpJW zz5J-OaaXi9p}(bq0Vta*IY2|-N>qnSV0V45lQvCQoqa9tkq|ti$uLFyup_@ay-{~9 zf$2EZLf{?OgF;>zT|9>>@CNBsWh8Xpa5J%=(8Q**69j?qx4;38d?*BZkF#jquo3N3-=qCJ0?@rmi zbw5a&dReB!?z;4Jn{HFbF74coQV%I@X+qNui#ia+s`QP^YBg;~{rmfK?+)@{pSHa| zh*#~R`?6n2Q0TDauI_|Nt~d>>1%B8Kw!!_jxM#7><5Z;gcYl`LRnKaCuBTsZ0`tygdVR^h;XWl zgy21&OkH)a-+=of{(?u;ymM*-gmL>0++-uwqyDDGk5LSsM3pbHJ>L&mb z>tRq0*7L?L8-v(pNv!MJII>qMc7N^ox|>V)qz|K#a)?KRf^8<^bR&kmo2I}i;d6TO zV>{fH77nxajgY%%g|o4DE@pKH2haJIqYf%hCq5;5EhqME#PHkc*tSih-+eI`?qYY{EUVu)W9N2zLee^C? zR#u|?Zr(`ouU$yQf(1CV?oGOShbE=BE~_XiIe5Qq)t}@}(tdU=i@9YVy74zqAU$cq zKr>zZ_ze>}QG#eeYRt04!VR}S5TI3>9|T6PYF?=13&>%EvOCK5z~@P5t(ue{zsVKx zN*(7Ak4UQ^3p-D21P`wAJOa5!I-80b5@}fxdW*lqo&tz@v4RctFVXi0qg$3PC^2%~ zsam+&l2PiF>FNC_p7mg~Vyi08Qb)?vAAu}SI=N?AD`}o*ck~lSYZ|qtV*BTj{HXT` z4=rV@Qa{!?iaZ$+75C8k~Ca^Q|T5{xTB)qdEgSN5=FFYn^tc9kKM` z%AGzKXjav^1c1>|KI1d$bJQgNxcy-eusGQ+Pp{pHIidxPb%T%79H6$uV{qHUDy_wF zZq~(StEx8*%~;d*TqnZw7?~=xt3{>nKgP9MlY0qnEUGoVM9ZQxUrUQlJGk{(F8p*E z4bCVo7;@JA1SX0C#4Whf(6zi!tvD$uNfRMFh_bn|B&I+ZX?~npw0i*#dSJ6e^$*XD{x-4}{cHABkD+^Rx3k5Z8SbhqMgXA6eU<@R zbVQNf_7tU&_$udu^NSDLkq*Dq1Z3Bhx0$?0#3%e+ND#2)8*|389W{kP-!Cw4m~}@+ zOw!K1e@+Ga)6w79M$>`Vsbz9`p|~(!auVW%8@p+T4<85~dHK1M zDdC^)Wr&l9N8{_+m}e1ut=$&g3AP;NXGjPE&OF%q%Jud2jdzIAP0Jd-j|&Na7%e(b zu?kr8scrLut?RZIHDKf(VSlj?VJQZ*Tx_{)uT9*o2nhJbAQt}Xs{4NGIDSLgjX8Ih z-a}T6iE~gnyOskeC(GOojRqGMiDVD!i^!jxZ+jm?5AF-?o|Pr6>z3A5`lLQgj+g@T zHBp#O!rqdyqFMp&!y#^X44ZMlwIknpE=^-Ek~a+nWJ87}U> z?r4#gk)c*Rk>|;p$1_jx=W<0;RQ1WrKXKCY(#88`f%OD}adkA=hR$}3l{z0qpu#Z` z^x6I4nU6j(s#}i<`)u>zX?kq+zsdj08H?AHo0f1ToU`22k^+Lfy9or#HCQA9KcWcl zEMe)44tu)xN3SCR^aCPRxN2E@WuHO^TV+3MTTjdSZ-Vt~#N3j9&kmLoC8v4|7C8Ck z2qrH5;cru{?o%f9{e(iHgsB)IqV0_}glkN{{T9zd3acPHCQ1J(+&{AB81oTb&vk!FNMnV_{CoBb6;Un1F#GmInqH<0^Y83juFS4hf>`h_g?@REe=&Rd zdG>m#TCoUA`Ln*x<%6T6qmvV7ZMk&MzkGfZwW$mVfl+OKs=H*6rn~zqWf09A5yDTO4QN*O6&v(Rn}IvCjc#?U`_LtQQ&%3 z#5s7KQ<}6M=`+E?){daBU!vE;y4Lvz2Vvh`b}GL{G`#+7LU4Vzz;$1Ays`y&rYI?q zGl*o0tXgU{er!kn@YEjgos~E6e?)lbbrPF#fKgjfxHOr728fHq^=stBnDGI@l1DJgTo+mhI2h*NBKjv{6^q*j7GNpS$C+xu9G+=YbMAz8-f&di zVJf#VyNk75 zPP%rj9cA2`K)?u;CY4A*Cj>!DJ#Qmh_%sBg@P!~ZVd3jGrKg}y!E;bgd zFaMIYKasY$e#ueDpp}#Bx1)=1p4Gzz)E36)-+457HjC1e0~IM5PoHu3r6~Lx2(zBU zwgqKb{~m9DZ#sr_f7f)wTIjfa3(lb26)4xctQ~V_gU);J_TQzU_NN#{Vz~^lSNTr5 z%@pOhVEBxOep_CYRA`c^NIetoAb@n44*9i48*z^)iSE!Y7t#nBOn@;x1zmSYiy36pO zUhu!MLMc-U%QgE>bpXQnAx(qlF=}CcXq$A%eiV%0X!_D;g+1;@_AhK*@2) zFORXM%9Ft^3P23@oVS0WUbBaMj#8|H2-U0KInzz^;_ZoWBfK>n1}F@;=HG{Yu^%b3 z4}9%Fm7brd*y(Crqc2A>JuET4}PuJi?N!YPi+Z3+GaB_RYKgPCN!ihZF zA5@y%HOYa2d#3U%qD13wB7hfBf=gd480IJ5khAEK!*U-{b1ax{7X=KgvaenA2L3km zJWaRD*Gin6*yvxNn@$bwJc%kM`w^Q|kZpO4nX0Q+7r{5Y+#HP&NZ4;Y`5S&a2k<+$ z*Aze?+G@eBK&+}Y0%3mGL?kn58Pkh)E;CVz@QX1py6lYW$@E_Bak6PG)dv{0Ch#Ll zvhpD*D~|mqy!#;4(KLY673dK+L=mKkJqtT+FNsXoc)YQ-d9ZsIv!STw^#*0>#T>fc zqJ*nm$uqez{7G572N%R$>D3;4TEeB~<8H5-v6A?c>bBMOZ(xtGf6K<-@a(!>WKPKh zu?TO@ZGO%g<*y!V6USyBt&(paLzc%pJ8OKaa#oxv4WeL__^$7B7(d*<6sy{Wx6?Uk zmm;UylNj1B16-A_H@+^j6~J>jxgM2Du7#H||AAQlv82kTpP?u0T55h+bLI=a#2$yS zO7{qTp16}dnSgp%cpgnY>tfyd%wF!vNOPzC>D}a51m4UNHG2H%_S`e}qwPuV2XBVD zaO*#D`9Ic?=VLroSsLt{%h?8v+FMZ&5F(e*+c+g2t3K9Ua5JKi5a}7D*flfaYctks zL61la`CqViqqzqqkSeS_8$3&7TlIdzTiIL+*8A)isUMZdgYfCXk0)ZN+nJmv z8uepcDVrV}8Nu}Q?X(OooyfaxgS>8&hpH-qqrjV~o;NABGnUNh}s`QPvV7-aGQMTIdDMcK^N(b1krJ%D}CW&1+Ohu!+O9Lu-5zYHWd0+;KC zN#8Jxj0G5K((Q^<-x?Oe8myaX*E&7FamJ$w7OYv{#I#5+`-M& zGn@yAU4u2_Jiu3Ms9YejR(BQMat({g|Mt_ShR4;P5@_;UyBwC$s(85G@^LogbLwdj&c$5#2QlEl zT%Me;B`h*9GIn)O+pv1p|A{s-7iTpr4?`3||MGaYV}T&=oM-#qK$B5BcwNQ>h|2(~ zE4J#DPgr8i3rCLH*1y}7uk0KEyhEurWeI;l-3}+BPFm+HTM)Mb4w6(jdark7k4jXo@{~g6<^?5rZwndFs9J zL|9CWf#8F^3WnRLg=Jnr{;k0BV&T20NZtuv#Ey-WRm9*C_nL0qXEzFRW-lKf`W81n zA{j&+K1XUhCTvi}bBLfKD(Ck&DVP@`KMyD*C%U$3o#l8dZH@3IUEnu@UA>K3HDl_a zXE95_mcc%IDfv~vF<-h)t+@2Fox{t8oZfE`%S8hkkO5<~U)BrT4^(lmOhLWNQqeRY z7(>`w4|V;VH*`|~L9M18C{_xn($%-xZQ+P`GhnWHo0Sd#(wsCeZ%Z<7J&dz86ciL# zw_E0R6Z?MVO(7+L$<5L^laWEwC~L&8g7H^-C?26^I|4R5jFq;S1OIAXS!AP47I+wR z2Jl}dN5X^4#CfiITq)ATGmz0}hbDRiG9x?+dV4GK&+Cjd)mrt2uCOz`kED>+0_+}t(IdGR zVxE7YK#634n9vzV@=ms~r3FCOQ`!J@XeFGnO{j(}`q7UkByhrizpTR|Gqknc{l@B=xO` zh)D3?)}X0UJi)-gz_P7VXt(@j^>F&0^?$n(h+nClt-$H^b2ix>IqE@rIO@YdV*XuF z5NenG8@?2Zx1_Jp6#}rT*3Zs3=tAV5lZHI=YC9zX>M^h|Fj@Xa=x8ATWKb*K+McY? zjs@Oczby2Rd0{@;ZqQ*U@S>TivsrEeLJ5jTptqg={}^hGj43C188ME(K{UHX_W`y+m1qp#p}R z7yiejVz*qIMb-cj%66@{!mW|v16Pi)uqrUH{tr1-}q4D}Ifp|nemjdb6tOf+57`ub!J-wt=J;AR&Q`$nfc z%-ijsKWU#|T+{<_GaVg7?43SC;&$LUMPt&4?p0QP6kx<*|F+a@`GvChUqiH*d~c;&y1W zmtP}|#E3U!$2N=he4Cw+P0^!v%pR|5OJ$K_t|W z&h9AU`#raITAR*-OkWy2mR)K*qkY5yD2iToWc?MI7$03~XfU8vpW^7gukR8HrV@*0 z5Xv%mc=d);@u@aXlk4GheY{TtpBL>f%;i8TH&cT2U%y2#S#JN{t&rzNxf~1z-a6?L z9i9EKmB`4$h>RfCYR|q`5V(X*NlPR>i)1nZKohlM-nsF*U4S<{JwlX>;VTWsXBuj? zGDCFlbreRwtGe!7dY$4B3dLHx?L_K-w7r6xGhdVaiUz=SASlTna+;V1d!v%admJKo zLz?5$Da!iI_h}Oswg+wM6rb{0n5IK*-L|h1T5~v9o`gPv4{%&l{rWv9WBu?>^y$Jq zC8_5h>|h1@A6m8cAy%k$wcZ>S~mr059*GqkTI>I4Sk%tJVqV=?Q#;*7I~{ z2ZRWML~!{LQ^XEG0rx`M0bef8-$c?8EcK;|?(prCu95I4VnK$y4mC4%jQJ8@Ou% zuwi_y+-Q7dG)^{_wYYE3h`S%s#(T+xZ)^VK!r&_;AldRmW_B|H;pk_QKFj?%Tae{A zf7NCqkmslb!fJ)vl6{KT;@!^B5VoW7)-5(#RzEb8+Ba_f!9-~`XKMM&GDJX1$#(p{ zEZgc>eE$KuWtS!_VDH%6n83_cvI0ra55r#~i8^{QmU$NhR8v@|6@55` zyRhf__L5}G9`MfvX0l>B$#B|@^G4kdZEjk=f1?dJq*bK>3V^!L(-)NXTa;3!DqF&q zBGej7Y9iF8=$2esKPLRh-&^?5!s@7gY|GGVKk1DO!u?|;$5%;xnSOWNc$Z(Q9a{C; zAJVAz@x7&wINkwzdDH_R(c)Z^lZ(6YxcgUPPNgKy-{X@700O!4d?R!jTKPG%7xB^- zie^P=*Scb}`>hGdc5y*t=xZIV+tQh~!j0R&6|OG(X--#U-I&!@6e>_)6TS~lFFzes z8S~w59|I~uW-A>gPrJu?pIKf2bx5wa1)ykHB;2R*p`9@4s_ zrAwVU{ogZC=LWCc025}en^I4;D5{ipph>3Xb+<*6zgu>R1*!td1EXO%=F!-z7^Axq z`uh5!1g>6TN8A7@wZLCei*E@Ii4iR?o`N>O=0e>00LNh0Rl8wQne6j~B`_bd>fP3_ znJ;nYA1jD6s8}Qmo=LbJo2gBh=p4gO1=URi99i$*J2^Co#i~Wrou0+WXmxJ8lxPsv zc3Tr`@?BO{imWzEK7O!E3<#5yG6dpPGUgp;4$_~Ujq-R8 z%q?(D3(8fzJvx>lg~vVIMGPd)`q_`hdAF=fxz%>k)#~(0GEC0ulH=GMndI46cAf$C zkWvPny4h;qJ}H^!ZFYfk4(J53@ug#1Q_>+?Zg1^jvjV*NSPOl;1DGH$a;ZLY_d%bjjcd;7frqWI9b26f?@6**^U=*r)17ktzsE(3* z>-2L)q4MH+eNgCu>TzB9L488?$1tGY=X6$$5DUUe)nz|& zW?@ob8{mRQn9`?DmUZ;E(y?$cXB)sdCP*qj75YyH^U2NRWP!t3G(i z`#3_enHO&w}6rZdd8$a3^&r4d`qIyBWxL#1_WNKwIVmmX&wIOE#@5C>5PL| ze$N#=N9y{h9rQ%glbJRqraEv<_t#fyMcCaY35>zyodTo}+T?0`UG8^lr5$lIp{`FF zUC$z>1vg5)(l`Afk|G=%Ei z4biC1W)q2!K< zf1nR9H9qWk_kE_g*m@Z9vUCKg7*wF=pS7nwNc+V3t2W^9jh%e=yZZS~Yjry*MJPiZ z56nA5RR-*awPurYB4~~09!XfO&}qTe4+$#1#6@8r9`NFBX z>xpzdKmY?o9zvLsmGz3CV48iVyhC)j(Z;^-cSS>3yHLC7_fm7v?%6D$24SUT+X^U( z_?X_<{IKVVVAXs2%Vt;@XQL_fcNlNq30`l!|8x!6`%*&i(k8OKexP9Xy-Rfib7g71 z-e^MwB^9{4H(QDn#_u`uiK5Lkjzy!<@l1xy zWFg_eBPTkH`nv|oQz{z3a&GPfzz)Kng>{o0IF6u3O@(K%SM-ah3|FAmpc-Mmg!d0X zm+e4FO?avUKk}l|vY*8HzKp!*W#d{MeR_^xLR)6mmRfPI>W1H7r7ur`bWG_th_e$~bWA!ZGkh{TCJ_13AD2?Ar8IX$ zHFCTiHOJ^}>|CzUEAR6kFjX0Ff}TSlnpzSZ>O{>;J>vE!#un8l$~WzOrz-u8gbO*S zs#}t3UNJKaUjb#jev5=_fC*XiX`CUEBgOG-)yr0dY#fiy65kpLFItaQVtw77UFuw* zA~#$2Fm|%o4-x-)YW8>7YEzcYSm>vAM8kdt>6P@oSnHqHGe%$J5XHWk7L4 zvvwU6<>}VZ`A^<|U#*-OU=Y7#$=56Y$ViK&e|^hR_2S(wxQjD$|5iGOFcRlJ;ROxV z^WD`>C?})csG6a(+Hrf#jlg!s1yWK{MZNc)<*?5fI^!G8Hq$N-md&=imjp9SPFr?$ z64B14TVG^hKouCt(T^w};rWYbv@#}!jbA_EXydlNan#~Yvuld{sAIM<-%)zs#Aio9 zzt8QrRLVa<--^lHwR=5CWn7<_PkDIQsUDWDcb`FqFAeF%{_;JvL92*f~S=~3xm=L zotxU7gw?9!xM?zuLtVV0C}ge@Q3nC}@Cta4kF2M!f+nuX$UFU+Q1hbDLPYVY7_pG+ zh{1ygz%@mkL8wef!-#;W_{7942j@}DK~Hz`_I-fWk+}RuD;Ab{CPUX|1+=K{H=N-R z+>HPDKCMWt7}MhAv@J9!HWJWK9EFCEI1nfo{Ta&_3L$bu#Nu;ta4;*TsZ301t`-tR zTR(ZR695sEL;g0+Jm2=rp$*Qc9!e579zsBQra5IHpg2&35NXNcbD$OhSV9jZHlDa1 zwqeezHh9$vmX&#QgZpZkWbYP&fXTQ(nd)dkLE#NBnl)t8_ z)uO-LXsUPNN$=wIY9#_@y~FyTv2VdyPt^9qKYUogLl41>etDDX`^t~HJNY@vJCW)c zo#&rYV9&bU`O2oC_yYatB)fm3*9l^0#T1nOD)&ZLPYE;h1-Z0mDAw1*oJ~-T;V-iW zi){FRu=mzcadu1IC?vRt5D4z>794`R2X}{{!5a_mq;ZEN5J+%$2;R86YeTT$4&OuO z%sKD*=FHr+?wwid-n+j3Cr#GV&#qm&_O7a5)vh{kg+NpmnA70O1EbN5`=8c=4Os}@Rs1_b1D?HN{l|o>%c%r3N2sxO2 z<2V&}S%ds+5#aLsCh7zj%}-!hg*0Hle6&}1cJBvZ_kLHuiprepAWwiHvp~5pD>*ez86AWX0T7oBb{U2ZCxliTf>>Tf1 zzjA-*;Y>Ev+AX%z_8(agmk!6DrF2+9MN^gDTq2gY{vVkt=!5+lBdqQ5{>UX`?ImP8 zL}uV$40lEK8|c`#_2!~i;Ff_Am1f7^-` z_N?+>M>TplNwF`Xylqv!6=}qxZv+TlOi;-jfy(EPi+9FS?Exab#EtZf=A)3rU&iYq z-C7_zc-#@o+i9iaA=-20A74oy+WtCXOyS;Q=yCmt!%X5i2S)(?)0X-DQ+9Q(%F5gv zJw#^ASJk23{8{B)!y4%3z7-Ul2I#eamlN1&@Py9OKB2!%;L(Y*#Fnwa zqo9259s4Ajo};(^S8HMR@a7Q<)sJ6M!C#(Er1k;|eL$J6f>lF@9a6^iW8v0S|q?lMs5%u5%FSV%ersfh3oY>9qMEIrO-%OR`-`f zUyjQ9Mx<ddvh8+!1b^8r=v~q@TYX|rs4&KS~wSQljQOe@>Hs_~P$6OYlbfT0)m0N%;P3 z!dp0K|F)INcHU<%M8yx-I7wedZ$_g9)09{Ozh)56U=Bhq?>}Gy*FjFMo2M>r_KY5H z0Ng1(Tfc0^e)GfM3AFPJRVp|IT%#r8Ph03rqzf#;^8j0IaqRsJF-laUTh@r*4AUMz zrdzCCb$07=IAZ~ch;#3QlH{npcdy10-eP?3rmF6ffn8b_Td`VX$CwvRY|$3(+qH{wtjQEyJ>aa@`JS=0 zI@P@tXSsPDyT|JD*eAqM2|BHkx@uou+B^k$W4cE7n(h81H=hA#GL`Ahh|ai^OMBrX61iPV|LyK0GPM1AU*4A zz7$b$uGriITpCfm$N!v9`;l;lvQ6Wczs|kNW|}s#OkTgq81j)Yb<_RN1<|aIidd^i z1G#M+Sw3H_K_6p#)2(WeY4a%lJ8AV!^QmlrNs<~)?DSVBedanCl)A8x+}7&ZKZ=?H zOf1^&_5Qz?ajnU&2RO|5l;0F;=VB$2vAMWAPN8_j% znSZ1G^kf0OZ(=|UBg?Nr__JJ6D3tJ%cxk)Hf6Sfv(*AaG8JiN(Kf(*{kbymywDfxR zWa{MC7CAd1sp;B|KJ5;RJT|qrzTmX%w@)_M|Br^Vwrd%1?;cp%exLqyy9W2?D9v+ zX4FZxU(fGm#N0H^!Q83tlhkhp^a!cwm088(lT@G8?7?S&_ijA?Bi z$(s(@@jcAhfJRhCJQ0+Im`9+9)xKSmlQ%0hKHtO5H0Q~$J)Q>76Bb^6?M(}mx{;tn zP-w@;8!;DUGDt3tJn@2{e+|gq)JkDRa`*C0o!b3UFihG|~+51U-{-6(%>y+DCKK~K| zaVlFmlIKbeVCuURMGQ5elf8a{=wJcx%G}aU@rH!+YhWOLMx?5XpgHeb5_DnkK% z6lu>$u(lAq_*zD~=A+I?GT7m9yvfz9FZ}puufOvBjv7h&$O@WrnKh*B}Rl3PqgN1w+B4X9g;!Qmq7;zN|um*LzG=fyGDcn~Cn;92`%}Uwi>9KT(1w z<9&&4No?;%Zx%Vyv#Q*E&p*>i22;OoMVepxsGEdYGcrq+~L<5uw(D9 zokiIV>j%Y@A$0OI`b9r9wQYP9#9ydGLLZ~iQWV|-@CacxEn26K@DT@1(-M%y2B_M6 z&pCadlOnUf*K19)irPPF)^u5b!}mh!6RvBb+B|AM}=Q zTlKutZ?EEFbNrVHmQ^?IoJoqHMZe^&jLXgscMYUTvJjIxGmStE>83m@z%U`A-Tv!Z ze)>u)E|!@$HSSH@tO%?j3rC{;g5qm$eLpthDp21BPGp3#XZ#x4R5SGIVZPKyR7z9++|afPvD0S`d#_dxL^4;530W@x#~%SsCSLy)Shc?dz*pX05;ZjSkZF ztK%@C_#jZ(dAtCpvrp8?ez4vUWN+lLBD&f6p2p)7ctQ>&l`R6nA{AZehfFLCbd9Z7 zLP>LaYCV*tpsZ0vtZMZwgn5IUI2e<7>E6%qb+}Kj{nNCHTi%ED#Z|?0xc~mL?#+{- zW#r-Lixx%EqqZE;(uyP}D{`|euq?Gt_#rR&sPP@PU# zWQy5^%I~E;2#qcaaov>LW(~BBk}~7q`v9VSYwTSrOJi0CIXpgyU%4`@_rQA5j+2r# zIik%Tvvisj-^c)Nq~&UzBV?iNuiVg(zl!$2&(6ka2{PR{kW+Z$jnuN$g+n8$y1PKzOI-4yrW!w51*>uHS0XRFX;uyUBwtBm)JckHV zE(9_8X)Q+d1E6t}aI;ek1OVHU~}k8uZXO8FzV zi&<}k-wRZPAql&U?-<60IQ&rC+-#K{{4pQz=fo@ zI?8td)jbv8`CTWdes0)j3t?uEAo@AWJztd0wPA7tS}7B~kd$e-CT)prWitMx59QG2a}Z4i1|EvvZ~C3N&O z%5=!Y&fLiCo~6A*Yh~@-w4V1fKq&HqWaDe*6H2oE<)oHrqdI^)Ae=%^@4r>Ae=_QC zll?uCq6HrZf0MQw*KRh=k|hoh<;R#tp?!aO_1M#9hWZvYi0>OR$kmkwM@_CaN&;3>pvFH6@YiBs-!zv zMhKk`q3zvMOq5WJ*g%hju_mY6jGv@B^^$Kbdj?*kL`o_fM;Ez!NEvP}TI+xgwhN~U z6b-D*PuVJ~vWrm+cw_RMEWgt4TzF3%Y>?ho;89YWl%4M$51r~9qY3!m+V#$dl^-+V z={dZSF7tn+pnQCT^kDXYOm#DPvE#$q&dZ)#gPhSWGFI!s5Yx4^fxPbP{ z)N2!D-guvl17L{9f+r+P9sP#3FB4ppZI>>$SN247i&t#3?jE$IvVD=R)sHiRGRn5h zZ2JeeEH~*#D4**{OHH%zWf}rUfR;ac%1RYy@(y$MN{n>I`|oZc{V;=mNh zGYvxvPV}I;vz|aMl??~4Q0v1|wG6*jkb_DB(}w>-wvb-6r|p?Rg+I|CC-{!RTZgat zy5{P5z%%uI7ce{iH>m!#PiCCHECez$Ei|6(v_E8(F;|e~O`L&o+#$D^>xQ{6chG|b75$uK5;JLeIdV&b%4<~KPawnjyRhXT*xeBrp}E|skW7{VgZ>)wK~ zv;s z&|8-A`FgKiwP+0Q5@O>s+2UeenZ+ zhPnBvTT%XNTke3~Kht67b@kpLOnS1^Bau*dAS-?LQJP-z_wY zT(r|a2t`MXKlo3Vs!REtw(&EDBrMBIDS6cKkU~;gd)QGm5T)Cjysh-AM9)A@A71T^ zWAclqqtH&ceSh~Q;{$4alapo+<@54Ru#!|LA>h$Ujj~}1gqiFZ0~T0U5;y+!HvM_8 z)u#1x!#nvboo}g*r32l`Yl)2pybDb@l~mODpyfW&^2c`b&FUO+GF_W?zOfpyLvoS^7=!3 zFKTBwGIa;TbZlFI%~vaA={zTVk<8&ZnWk80v|Mta@c^p5vl!b)Ry-Z;x9e2?O5BqZ z4;H0jeW;rYZS1QhYV>`B@W*G#1?43GCe!zK^A6eeHM-+&xA(1oj03G{paR58W6})p zOVYdO2S&*_W=>MelJn{P8e#sM2fOmCp6%i2=GWYNGvKepIEdW|N@tz}TYys(Zy|Zmu z&9#hwf=?d+`|nY^%de3l^2oOkT5c`~)TPXP|02 za9CtF){+?XH98aPW6FxMl;tOm5%Xsu&o9iMxS?G(li;aWqS?D~yfKUg_wj7jvTFCq z*anu`yToOLU@ff1v0h6mJGznfVcdkqIstqs=>_Qd>u=Vm_phpJ*5EbYoo>CST&b8 z>C-C!WZCA~fC}ac?swpK(4V$TE^Nqv?%q;GZ1ctS`YvU*^hIo7R0ioWV1j#{0%0S- z$WK$qb^4hd?aIO7E;H^>FhQRrH~yR&NU_*5)~V6u9@BnE^q13KUIQpc;>vXbq_1X# zQsmgy>g!e=2(W!;leSgc^`yn}gP6Y3F%OF#G}W&B@A)9wf8K?t?=? z-0uSxQ2aUa01yNSUT1}F9-Tx6?+{CET>bssLJ43;A^lNLV*f^C0(dA-&3gMC`$waB z*6bw_O6jmV!foV`Ju95|qIYNJ=72CO(5UblD@y^}>0hB1Fy@xP(*8>v1r3h?G33uzZ_e4$U}g4xG9#f14u!oiVw&Lvx^IpXNu#BD~kjH5sR z;~svE_%sE4j9?RM@2om~7DQ2F?{bxXNp&_Gm|5~|(m$N#H9j}lToA$^9<77jhx_w3 z;lqxPWJo|&m#SMXL=Nu5)xLL~LSV{ifee8s zrn|`xLZW7JxH~ZGFmzJD37BcYF`dDujz+>cN3Q(IO2Q;@`Oh!CgcgEANRVL&fGiW3 zeR9e@!0A#Ntli@{d2*mqh>8pfrI@l7_qUSs?7YiIDPi9}|C`V)Oi-CzEJok$8vpZv3R11zjMIUK#_^sIVtkO_xag%DR`ZWn zEpvT_*>N-&4n6zffbX*)WdHpgL&|^y!ap(A-hvp!ff5w?*j08nORQhQx4D7OxBUc5 zW_rx>=I}O<{)wM>c90=}&k(Xh9%MFq9nb%?Y z3x4E2Y)k5KhrKzIDmG?+e!_pAG4}{%9RNmU8wtpJC3-ILKk?R1(cN#|j#vlC5CJmW zdSOBR(i|`9)N+u zGT0Twh@14JeK2p)|FJ~o$jw&VD+AXnwOXVKt*4;PzTDdzNl6SYDz>&8YFENf=zR@a z&N?gr5_)}mkC~{?bls>z7i_ZQ_fNdv|MbrRoA~gIAxq(tQSFxQb}?YYe;11V%silU z2E&>bzsa99XwPhRNX`hkGvGK^8b3BIS7G|QAmDoio6yl~e>t8p^1m+#ziXL#->{ z4EoOPW#3821f{J8BPs}7{V!Z<}l12n{cd-}eLjgOz+M6LK#R`@415Ww(|PY3Q- z!34;gn*+1wf`57_1p)ykZiDjlodrnMY0w+TdHSwTK?zJZkN)X5FZ zvnbI+{%Of(k-y*riB-VI7;EUQ0s`h4cKSQutGU zu|EyD{;9th-+yO+G2TBf`>*?pJw5Zc;^qJM`-=$+|HqzU27hfD_B5@(jq+bK4ddfx z|7#)hVx2jM4JlmTORY&tJ~MXn514G2N&-teu<;J{QxKR9P%d>p1%)aB*ty`8^m>KQ z4pYUftd2;mI^HukUK&_}E{8FarE9dj0Rdw&3^qAe73Un(_B77KI+z;bd z!5{e=VN3OT`)|ara;`k#2v z^yyWU=%S8VJ3N_pngqQPcNM-;cbtot0t1@Y;>_=q7nfAa?JZ8HiUoMj+vuK6oM3P( z)@;5{dPr-4@Q}X=j!V43S%&H|($OE(?Ji&e*TM=?c{N2!ALp zJi%>P6}c5|D+FFx&Kj+!6ecxB5LS6nA4IIZO0}as+JAJU;p{|-=Y`{OkHAWy<7{}pC6o}SVBr6DI)G6kgy-!Jxt?Y4T=YoQ_{&7gsee&bE z$h>U0o0jcMct-42h;4c;PP`gtf!dhKx*0=5Xo5Z=^s zq~+kMXQ-6#m?Ta<$0usQg)9jIJ?@U009c?Rc_Zqv(ET2+iu)S>DN8#uR&(NfC^d^ zi$Qvp(Sn!f#A3GHL3F4?TwALW@K}3Y?51r2UXq*;dW7uvL7lTKeF-i;ol2qyl zkH_h5xM8N`0{ON})^PxvG)38S_(u(yeV)2*#(}9hAQ=~;2-r+law@Eg$BC2I%aN^iaU@pgtp>-&h z&o`QtxAS778kwfdgW^uhEM;>!x73nFsF<&|^sVqF*SYZJF}l=d-8Q?_CdRsO^-!Si zFaj1zgA-3YV@ z)}OIawdSwenjvX3d@eQhqzn0=IAPPh>nc@%7P2xJK8Hb$|3L6eJAyua=E4k-(JKC} z&FiGZ*qY3R9>(l0p_!(v{wdu&+_zM@R+P^ll9$S@Jz1SL+^?PI73m|%TqO~F@^^44 z6JiFS+&ngLm7(-_%e_%RCq3roJg!FOg zh^NCsl{|*n+lJt5o089%;jR$njQvaYcV)5E(O^v?5f2e!X9@wQ&y+*n#~P+iyrSMJ zt)n}k%y?tPQq?NiR6><}zTmt*p@gqeMs=UxjdNL1<=B>Wj(-Ser}|oIQ5*fPZqrsr zc@(aRsjJWVmm$^5yDN2VA$UQK&0qyXa{{Fo<+L0!dsiMb7OXXB7lhglsLWF2U;AQK zaZ|rv6D9A{PzlsGZGMbD4JgyrNVnQqw=w_070=BO6BMpQp*q4t?0_*${ii-{)wg2{m*m&yaf5m0FN8VGZ;vX3Ouuhr7nF*%J3zFbWx}SEXZ6@> zP+jAcsc&nkm{Z82nKQb6M?*l?iYOEO#Bof^;(RtnPm&O6+gk%ezMr3WL#6#Y@i4-_ zo?(L&U;HSBEJwbWF%Dl% z&?j8@a=kiLkmZh&rEC6Ou2rH zu?==HFr?mirZP^f-?}}=w2+2NLGteXhq z7CKzLqMRiOIddpTM?ugqhOR1!1aH;JIigNjjOeAZaA&19PTA>2f3n{c2#Yaac|*`! zv+UF#4D;>~+ro+$hR&@%MKHg%M?KQQ!)@0 zKJi%lwt{#hh693U9>BWrun|VV^b!BUU~<(2!gE&FgM+a-wGhnGLbcMAF6Egt*udBs zPdemj`8`-BrBR47sPVC|f>?J`S4s4`^1=DnULVCg^@k=|%%t|ky-Co_ekL|vHoo?E zkn%H*O!N*SH_IfS4)zMPO?u z6fvBfVK^d9n{Dbw9Hge$pnNzZw*%UQeExji3%Ax~y%nu<_)7o*yW>}&2scPuC#3j; zUqE1MLBA2-V5>=wG#v%A-uFl<>f>P1XA$w3W*l+akho~iFE2D#m>L>=Y9z|3RhVwG z2-+J7M623|dN2DQcEw?ler#sWyobq9$9rggdxlSwHI1`=zyQmrL2%jKCrLn)-QsSX zj;>PQ8&12O&umdMHuO~uEY0~{5xAJN^&CC}ZSkf$jg6gzIdIcDWR%t_XVe3>otJ-c1|7Rl%%lE|guA}OVIYMN0BWQCL17sI0NxUh#sPqT89b@n* zGfl9s!dXAOwD1FVrSvb0FMe)#_uAuzlm=Pdbfd~su%NB^2t{Arme*~(*hYyu^aRmU zLeA*DS$dhL2O}L{?2CXaOloK7jby4qZB4opvt&*$;R ztyc*Cec>I&n@ZKcNoP`XW20~H`Ve%H)m=7fOE4rlF86~I<^zR0YU00h<}=B?pW*kW zHDZmG`{eVMEN4aTn-A$Y-Xm!e#&0P6;l`0bZ-$!mayZXUXZLpfWQZYo-$)W)e!al! zlah~b-VgtLGm~fI6LYGW?XZxLU$6mX!Av5T_D~)Q#Y*H~6|hNJ z42G{bYMAa0DVutI;I#TO;am3}*Ji1Kli-WR--xo2_w>V>a%?+v#r8Ps1v%}zFW|jj zMN82~{7xRz`qCleuzL~oI=$_g?8k9iEtUkC!f;a^lc3Ab7u$^_J@IbI9EJB6YGtx; zkqls^6qfr(cf23*EB)}k`bz8L&I-UK{cOAxb^)rMyg{KeSv-#OeAigiUDDkmYN5|x z2Cj-imsOiA5`kPPwavq-&_&2_jm6^3j9w!hFPGs-PqpW?94_=Tvg7N{HKEPveIX~3 zZ-s%(lZuQD0%5B6WI%G;h4V(Q>OI9(HvT|DE*7^#H8mHCi@SG?li5RCt( ze(3-9`v1Bg`k!b1$MK3k)B3;0D|oor{)$&b>n_A@K+t`U$_ndbL>GXzLFt0$hvs<1 z#_U097+7SGAkFxN{@Hl5z9j+D_(yciK86L~IXF}WJvZ_wCPNIJ+cjv}wBRt0h~T1+ zrzc%BH)ckLmjNEl=f^AQWQ{#0P7Bpi151(%9@~^j%Y$*b2R`BD;)Jg8civTBjOfQa zTd$?hYD6%GhS4_0dy9OsBzt*{w8m%*E%x}|&o2|jPH@yrIK)0)|DMUvu$<8mL({To zR4U@<#v~QxLl2fGzq=&8@jJgBpjD@hxaJkaXgfQd_POr6<8Ui5aC~@kDSdisvlH&9 zOKT&yZuMg7QOPiNV6}IyxT9n#8e zpR*IUDqg6^YEh#j`BE^SYR|vnJAHGd(_BJQMS+9MA;_KVbDb=B zcKa7s+Z}a5;Z&=^ZJpcRSPUU5_e7m&)5h_~U`Vbchy0u5cX9+cQ3Ta5YpD5c#lqUz zP0n5U@bx2@`jXB(!rETQZla`Kaw>L?B9MIRd&WZ>H8{w{P&{n>^6NNRdTB?@4JkTv zIhz_{5+r5rw?i;kBR$xJKWD&ta^g(zY&twZaeP02E_vB53YD@w>rw^1DWI$PjZ|@m z1pzm1F@Y&R72im6IKnQ>aFP{aaUlAytxsdGBo4TGk{LRtaZ<*+tDcz<`B`S0BKdw9eJ*cvyMS6`F>l&v7tK!hDO-k-qED($(R(T$Z&g>m z>=~>5a~u6P#8n6MKish22DA5x^Qcz|a+hdxp2L~j!nu?0$tkB)M#hzFvkZS3`P3GD zXlA{v5SIN~%-;1qb`u$4FnlbRi_lx>N6=FF=O*g^!=GWL3ckq^A9I!?fQJphVF7awcru$em*!d-I#Csu}Yt zz0l5KT1GjOYU-}az_Ts{6jm!*TG}Ng83yWOo#?}_Y$;#`=_{u@hpAl!_JFpPfPh?xxeDS=yzyS(ITWW=P{6OZ5Q{v&P{ujA2@FhlhUr)ngwvE;m zWZh_?ycIu~q+hg}>a=u~e@yWE(5e(363^y4;T%iJsGSIt@21m?M@yc?ID~;Dc`q?6 zv24`&EG6o;rq3-}m%h4jGJqQMqlrgLIRRd<_be%7WFq2}x{u{~A|l;UB)d$ec~G6} zH=RRO7Zql{LX<#BDSFYWaE?l?c7@>xg7#tySrlcxAc{1PZaOu;sfa$*I+hV64qBZV zi{xjbV#5*#SG_j=*0C_Om>*)zoC#b;nPZ}&&Nn(<937svTz5T0s#d&nY6~r2RcxjD z{VEr8F>^cM4rO&JlZYolpM9Mbrz#2`QtbSCh;uMKHmsLu;X(gM+jfzUd$-;Cw-EV`9J6?HL7Xl)|WdI&iQ`n7X8?i>NBMf+C7 z_^%4%B}ec+j!nO>WofcRPWaHl#?oa$w=WCHdad) zew_s-#^FNF^ZGu7MTvnvYy9Gb9~^W_&-lodVnIkP-D^1!NRAOL#DKtWv1y;_flRtK*Du(BGk8C(mF|Q7 zfRaFwM^)ny+a8_y!K;KgUl7-uz%5d!CZ(|ZJWE3{0p2%Z4ZQIZac)P4A`hfFF5cAg zTj@syqU>jT|I*?28Eq2fvcHvUX6AZ7bvs$la_AH3#=yaBXTnl{%?Gm>y)Ht|^v!BQ z5`yX^r4N=QV3V(z$yn_(g>cZm({#EI?3BYoyx^tN75wtLkT-l|8TS?P2d6LbD#ErO)lRLA@r0zt+dF~M z)fa7yJrmP}*m!UaIB;pKNS3>|WSbGMULg0Xyu}X_7^@WP_!+%v2^LRR#pw*M!Bg=e zfKU8}CTb!$pov&rJrhSR@rv0#-c3_=)JJvx>KU6xoSmu)AAEuL_0G+CgJA!_uaIX6 ztJ9hhcll|^VdS&UcA`oCVwD0!uKO}Nt<}`&M3<< zF?6Bv)i?OIDNN*T)(G&6`^Bt6Yhjy~5E-0O6u|rVEB%+v7d5a8Xi6_`NsXK~ zjZ~;XIm~czn~og=*6`=6&-b#yq~H?2akot&qILO6B&!^9@j?1!1EcFb%?v{jB#`ky zC+lUqMb(Z5ivIAZyT~A?a|<$j8f*7#I*aYsUtdHzYZ87EID0YwuC`zgJA^CdNjm%? zx85>3CCt0kp#LU7Y-6CiH^7iA?`M+QS|nGT*a`$!SSXJKgBaXtT;Y8<#}>?@f;$$X zo%kwz!S3wM%rnNVS}ZMM9H%S8)(In`emLjH?H7nDC0*ZTKZMR2{1!*V@m&cGkDs~;>qlS_G8-zV2Ay*R4eM4k+3QbA_I?Nq>(q+bN` zBnUJ57Nmcm>(MD)oV~YSa{7=cxmO*fU5mnsM6y)HQFo#+%4z1xm(Lfbi9vZhM|s|- zm9~h9orh73JT#Kv*sy2T(XVx04O=jBt?zo!lUE>Vy`Qm-}us>!}?407Cxo%tSizQAO<&H2i2(|er!QG6fUVOn-Xdj*!^ zB48leDJIFNJx$>IEIpQYIn)PB+{Fe9=LUyydvMbY23udVd1utlm9?9*UC`CNLLrp@ zlh}p#JLu?ovT*W|0KBZ619VNOv$c^LdzK$cS#k7xhj__Nd1&^1Svl$?uNTI6-l?Nq zS@n@vf6R75KtY&)O9|vRRaZ@8Zh|*_T~a9ABbS!5NwQQ)u>Tzu8nK+p@=v}1ld`Ce zs2Ifr7X#dQzBWN8r@ZjERjJSDbuOvf!n2}%C-He1pI6*k%l2kvx$=>(@jwR}ZJ^f+ zS?)0(jzU~bPX-1U&rgcqMP~U0m!4?!)(a?f)~}ixNU$$XBxiG0KA&`cRMo4_^-!T1 zZyU__M^3p=V5N-7Weri3=pi?MD9z9_qOM=hhtDr3JJ3Np(oqEURS=pg?XvUd$K749 z_3$=sP>?<}{N@ZQwl%ZaZQd&@BVBAMusG4=C)92i4XD5vAarAJoP=L4WEFSok%fV- zHG!eKi8%%I&CC8AE>&6*a>#+Ia{0{h4C8ApD>Y|F0jr<-)Q2{$rK$8M>uwZ40|tbx z>o4NcU6r^R&UN^cpp$~>R8inU&X10d9oOD?zub~7hIAD5WGpQ2y-a27Z%E6n;G-)LmZ#?naS%u?s@Bj(0S zn`j92V?VO7=t19w*mZ6Hio|w^5_i48B#E3vzJ+pm@+Vko(29Sue1eV_C_vEvHd}wUmF#Om)==a z7Wd@1rNbt@3ZCIm8y)HySxC=ea}{<=^m2tY#LboZqMEp;ki2QaQZzomr!{j9Qc7(V zg6=oD#Ll(}q--7y=S!YE=-{hn#=M9~_;{Eu8h9h+;DUI;p$3 z(kb$>@UfUWI@;QsINS2D)3d5sn7Qh4ym`aI$3^xA_=kssjFXp(g#-AD2Y8ml;P1`U z6>J=AS>J)2ELi_c{V%BsoKJN9j{pp;vi2rc7UBl1+RCQy0ZIi0f&bwn=1)U&aQ>yG{C}P=0sNBtulPf?_CoA}6t?e-)|naS>#=5|lkKj(pQx|*cy&Et ztw?!I<=;ok^iyyr^!e{U9)3rq2kq}Kn8KiUAC{K>5O!0lF}y#~v%A>%RWS5x%2GXb z*3P|%zZmu9S{!L52lChcL`nQ_X>+bcY%%X&ev_pph2Aqnf8k}%U=}iGJFdR5Tfr@);7K68SzXC!E1T9KNY)_8;AW!Lh)Hs^rqf^NSybp>>m$KhbGHO+Cw<a}Im+>Cj8Sw?KRNqd$mzk%lmjsTl)(f^D z3ai9Um89$guqH^VelV5HXItU~IDx*yNye(vK!V>yM6rU2I2Wi+_*bgSp#ZGX-we8_I zh6@#8Du`moe7b$>nGN{Y=B^pm#O@M4@jBC#dzh{n1Pwd2{4Ith(f|`V?%RC}u+edr zMOB&0WSIyYJ~lExlJh1q6z4e;yqXYv#5vs(4p^dgX7-XXI^Uu(HPN|S{0ELn=yGPd z(2KWV7%$$JhEZ6*BKZ`u$2)Lzh>};JWill+Myhy8yx7RAKee3GmgaoBM=NcIb!)!3$$5hO_d2~(_b`6$b4d&Ge-tbUl zlAo_orctAuoN&@(o2?L6)hzXV@zQyoUC6&Zm(!3=4EZroqBC8^Er-eXEl=u@xvOj0 zS5e_upR7-xoVY6x*UB7h4S!71+ir)cL}wD^JaiD`a}3MQ;9Mo%Pm=M~5!BmJt454I z%TuBLG9BHyyOvwS?bS^Dj}h#qe2b0tBN{pMUzYq#W#3Wy@{v=^m=L9z0@BGc1ns4a zX(p3&HPi^qLiK(mPmixkl6d!<%5U*QBMiL31v;fkt-G5Zo#0@cW8&vyS()`AIzlyY zsYNIcp7{kQQn;^oa}NA}vZ$)ILuepB(&AB75%N;7AV0&5QNjwSEPpTXNDsSna!1pS z(`EhKb+yWF=QeB$fOhaykO;kEs`_AB=MuRa-*esd4yRQB{g(6)$V-E-?GjcjO-Gjb7~LjkSQj)vC(0cRKNWBeV8zhhUGTM z9raKOP8Ghf^oS5$`8Srdi+-1SM{&2kw)w4<%<^ajhO6Sru=N#ar!mxbk={gLiZZ8Cl~{;0o2rxeV$lzyv~ zLs}~XT|_=6R>^pU&m`+u7QMX9Do8xgkzir^9$+4&t3Jv3BaW+=4`CuODTM$*5`v|u zsxP^(=@pPI82d_kw-}3Xm5*A;@%7H)huj}#kml+H;)j>+LT$8Cy3iL1?wayuAJ>A* z!Rl702A}&mg4Gt0rt0L5cXKCKUT$QlHex-a_z^9aeqFOICKe}eJ(V0B=0_F=DlU+zIX1N zx$~RPZ$4-L5%-qOleM2`?X|vZt?#oi81ZFWGAu355Sz@=X3%ev-*|TIi#)r(FbzFb zfqCq(_L8||^K-J!+<`;n$JHWtTSc6XsiJmlko8;XoCS7#kTZ7)S}ZPodA^C*sup|I zmUgrFDRVk+iKI%eXk^jjLz?EVkj+Phc{|s=qM>nt-PU4FcK%V{>ci`Icb>0k(47>r z0DFutiwwREUL(DrYj%h)(GOMCbDm!CIagluwXg5+@y_GJAWNC?Jk=#X>YzX!+adZa zEPL$vsGpMz&%8@cm%d*4P>*PAyV94!^5xc6gPyVA=d2fMABE6#?`n3q`a{{SizNuq zVZ+u+(ANtAnKPbXU*cP_4;fDhxh!i3!R_E3C;8$<$&5Z zUO%GK=I7ZMIZ@j+ma^Xz-HtKrFy**~=<8k73F3h#*7%lnEY z00Vu#ig&O35}sa@+P#S8Y9Cn@juggUIONTibMDnz$=?uCpBj(%3P^c$f_$ttRSvC+ z@>nz=n-)(zd1dn^eJrEm(`dL0%_@7-j}7Cb)85<%OY+j$w$aN4oQpuGrumqUJH6I5 zi#^W4ep?JiN=eZxD*9s#^i(F!W}}NFe}bsu_^CiOQYXU)eR`j?u((!-7+jJ;0{Cq0W;!-d}MzkCIA`^2MM4>jU(IwuK)A%^y5 zk<`bZjaNDEDxVXc@pPZ?+Ff6KVrW<+*GYHz^kH&?Gzm!}RgeC7BRIl0&iCk{{=NFy zwej~Am*8|i57*Z))F&Z3-o*C536=knx9k4M_lAp)7Toh8+{?x5k$|#{7W@I+$Nb?P zXBQBc`nx;3nCV`X`B&Jct#wn|#TkCrMMlrX-PP@pfRd7&jG>E{>mxS-*^7!7<(2=0 zNq>Wf{{l+?6(P!4x!?WmK3SDN<2=e2$_9k#3J4TkAa@^wgk>tqG~^kC`cDT9ct%4D ze$vn$qy6bU${ppJG0m6D5{N6(vDpm+JD-{hZ6{VBvH7FoG)vpJ5^4mdsjE0(y z3POLJ;RGWUC^pSs{uKNVP-?p0e#io$28E)grKY2&0Y9jHsi11d@wnJi zh7(-e&yug{6x3RdSxB5EED<|DFYmbcJx?jD>l(-H-t&)0EvoOHSlLt3wQ>!JOe=2a znZ)la>)mn-j7opg*!$(%&vPpJ*6xVtjFP6ludBfM%hzr02gPK*ZSJ31I{+V?8kF)F zIFWR;$7yIh!RKM6q5W0jW2T_Qbl%|!a(Pu-XFiTB2w!D4bMo1i7g5l9!jWh$`r5g= zo!)m;aZ&pz=glN=cDT63E?qk-e)o}u5+T2)L*m@n67gAbLG53QtYi6Sq5q#U{~eJj zQ;?H1zlq5Tfk6&|nD^}d=f7KgDXp?{s_3%+K<6v!7pQac4wuqjG`ESY3DCUuc3nNv-EMnZ|!u+Of%u zu^B_>rvr)CLGLqT${j25*7&QMJ^Ew~OPm`w8-!iMHBI?qUqz~N2KM9!>b^!FUhoas zv@Z8&`rqIQ98@R}6?O`w>=0O|Kr;6SD3E>qrU5dR0^#X63Zy`qnK<2%F*tHT+v1+u z2j73h`E3say_H9<^TUp$$u?JT2%{m_J;$GO(Dk09PY>T4kgQ~OMfW+YR%kN+S2)!r zG%>;PU>K8&0V+d=DUe55*~8y4+byt3)ZwcI|FoYKj%x-RGR_0^ivIwFs08&ZJB9+8 z2qo=OAcMgx$isq}6{HKObqnMczi(em6BS42@?fVTpXdcbS(ma|!> zp0$-=DDV@!w)Qob~QUYyuVzRELG9)=#0q%a& zNg@a5$9A$vMiJ;B_GEj=iC#N^AD@qv zOOW@)-uta)P4bDXQS|QIQE{)fw{-X}C1e*cD^D_1t>v9G&+d&|ia3mtU6fzfet0~g zcb=uf>JkyPVv^Vrjw^*K0q<>&PUB{;9~zE5sADd*8y;G>Zi*T0h8fSD6X7o#6Z-sy z(WdGK1KUMmwTsXS-(R9Ob5|Z{xVDpK`5G!hb;iT=UC}UQwQv9) zT;Q&8@AGC6k*+Nfn-7?4jw+hSdML4I!a{vA9bR|@Bfe?tS!IpxjAvM+%S$LSL>qqa z(p*$vScu(vDzoy$pVRUI9uH>f%WnZm-faz%_#nS zAp}JD-rgmZ#|#QITtQ%~Z@5sXkWhHdxf?XztrNTcY3}oA$JB;qnaq$LWI!dLq)Bke zbOc`9B37o5KH_-XJZGv)3)*gv)$V5b2}HeMx&Gul*3$I}uWL%U7J}QrEu3{NAz`Nz z5?G*pEy=K|bI6I6C*CAQr!hKBQ1ffG1iY6WE)o_LW*c@J5rI7C78Frcgm}wyY}|=3 znW@%V4%m=aJ~TyFl>P8q=V9=AtxI(`kbOd~pSQ%XtdoH@W@r2bC(p7Azc=j@Aw6ns zJ!(TEi$$H+LB>B#^l#9HOKXqNRjh++kxqf&g)ow8HRbEM4vp`L;^~SqQgS^j&N!F^ zB5m-})PpWsj8*IVPmi#N!H5YtzP!Y138pC-SF4kBU+~k!XFeA3=F49_c&qE&(XV|r znoj(oCZ;`&>v>QVEt5}4sH!io#cG?gcNNn(2K=J)J1=6-_pHx3P5K$x>eWqJX%Xg= zNqsAPSI11+94wR8F4^d01$f^UXWyClA>_Kaa7BUy?_+T8Q@aa~vy)q+#bkA=t68+# zkI*NFE3|uO3tse37gIm^TJkg1e8ix=#g9)dN@O1%vQOqbc0QGS^)pNgM>LAa1IkxC z#WlxBljLJWzRyz@&*xr0sAEk3jvp0q9A%aA3AGtr5hB1iSPapO<~lan%F#mdB}r$M zP#w8$ThN>OXb4+{a2%V8h!8zXMtmIllBVZkZ4*&Ac5&0|cc z4L<@*?pNiGFUq~tZ1H|ssI%AW^1*o7p<6_EbzzrEviZsa_1(;D9M_l1n~+7C+a5o| zQ%5m|QLnJOCIgj{^%%S(_J@p3v6>rQ{n z|4z^1jpG#!wwYSGZw8|_qgYIc_inrLq0}4JF7xB>6!e^a`|*VUdFu&%2yLe*HWlPv z=RE~&+Bsl;5Sjra#zB+#Lx~l|2OfjD4+!OPg)675MxIQsbDE3ZO&Y0>lSnMC7U2Kd zJh>Pr^;rAHFX12!E&)ii*NK#>b{5ka=Iv>hPuBfH^NqLNm+!Yo_78XccinYVm}i(F z*(xl+roCHcF=!fOM#pNFxbnj-LWfZ=^RV$?-PW6Lia6vw9C#i)!kFH<6V>PjbJte)gfqtfRnm0w`xV`Ug(;}Fd&Ml>#y1IS#rCYt*R`%JdCnCKD zv?zwT8_9WU-Y8C$z`7nL8OPGK^kj!75DNycP#}_Xpu#DJnW(2?oC9+Mhz+>xHq$^c zYn}YF9yXp!`VVg8x(R3r-g$Rs-rGJkFnw<$l|Fskn(qTc_tA`5RGXDVoDXO57_wUo zdB6e2j>->{pzBl&i7MeBeNFL`TI}Uj7%>Z)yO-;6w|+uxei^;Sy2ZqJh!$Kw%KG){rjYcli ziL%`nWBevvKBa0s$9-#%vAYFvIlk$ph;aGXb+d)2?C{hNI@YpxBjknrqmqY@?W0ZJ zP>aW(&i~x08WlYZ8J6_>U7p38y9A4p_z^qI}CaLWM3h1o)97iGwnU!nX zOh}o?dka(&g$bx(*}{n@Q?2i(D{2%YFfLM7L5Ad%?6)IB(zmUn%S=yff4Ge9bB|fn*3ao@@q@`+Okm0!yKd0Ui+Z93{m+HH&szX4I>zDuiL8ZE@iRjB;^nr>u_X?#nF z80vVvyM{H0glJ?)%fqClo)se$u6TuWMK`&Y&wwaHKn+<&R{}vR%Wmbq1=DLzQ?}~5 zhPe`(&Nwx;$0N`D>y!3s>e5BOjt$1hy{vkfB>v*In6mIW2Ik_Cm)=+HoQAiE4|l%i zm&b7raABW8oYxk6x-=qM^tLm2&38_(k-e$;@X)~*l|vLrFB<5YA1M97#4O{mj?8s1 zuWuRqzR}itZ*;YJckt=3OF%o!X3oDsuAOwvG_BGsP)Kn~MVm#Odw?O-lv}~NxZ^xo zV%v1HH1E-5su?M_`gFd;O$OAM@F^VuLwIo@ncMEccy0+k@`WK704$RtFrUQ@RN)uN z)`-b#BL&IHwmDaMeu(Xs=Q~l?qOD?=k26b4{J1V{^_2pdTU+|P*shx%rymU^8ZLy+ zT){XVb!XZOXZi;>Zin-1EDA);%Sl`u6b9QxqJe>VpkH~X{3_p-T38=OYBi|g)yGcG zgjo-HH71>zaj~l%b#4LEiU^}U6ZeGP+I>fE7r)~B6tAJZ z^6asCPlRdOuFL7($T!HLQ^<7zF*B}Q`ASE5D19AFzypHDe1HX%!78e35p zc_;rjBwv3=c-PW1gh_Nvf@Rp`)Yk#AfbKE|w$9;?b#X66Bx#P-*`}ALOkH~}*7C&a zCe!ziR|@sj^?ReV*)%y2z~NW!-cIeLtG#?mrNAf5!+ZQTgoaeLw7f5XYu}vRD5)6N zDr^5}UdCnm7g&4ofgqQnQcw2wQlWwPIoNVD6VaOjIyq5;Rfq*~*jkRSWk!)>Sv0@V)lEK`6f-oRKFzw_Q1v z&iX}_-#MKUoXv7Id4~#igWamtatZA{6Cm4jSmLeaJk;I2*7l>d51vSYh$AH^5NWzH zm<&u(EpJ({QYU`>DYls}B2~s2l}6iiP#_!hwq+`O?U+e)cUX%nZ$mi#^iEExH#T(+ zhbnS%c4yLkv+S?d{Y%IbTO4z*WA8Bbhl^UzGPDmR1PBkvUK3$mpQ2BDGdaAofwg0&L#>*%XdoQ(E%XwIw%-TE9QwleXFZ@v_^(g;vE&^RY*KyBZr4OrLIV`m+hE zs^8)qFh~08a`a6o?A0}R+qebh`qcY+OJcyX__E^)U7dJ3=@5`vHcQg_D(7dm+Hd+dnR+c*THPga*w+fz7ApX5nCSQdwBo7oX zp7yDRm-lk@&Z{Q7NaSt{F?H5OX=`=RjA>e3r)7~$p{C;NWLl=rZi!rm57-MJkVN{v zOwQa|_8jRnZ6Z^S=UeOOrIT!?$7Xzb2DMnurm(Brtm@WgqY_R_Gip1Pkp22NUHBJZ zGnk~Qu~nEC<^a(5Z+9`LhM;iZVt3J{@JF7sxtHPLR#Mm@Qr+eBn(GteqeSoz#X=#j zPRDLdAYce?9ouLt7S-s7aa`L0pF@QJ-8(hB$oC7f)6Wtm@5>2*VZIPm0&g!Z!FcBa zy%wPjRg4J6+9;yZ9-ZPpRyX=cU2aa&K=l@jsnC<-7Q(S-9$7$6CKsQ}N@&yiN%>y1N(1kjRhWA&Jq-tS@QeE~Gh!*&}%HX$ET>va7kmsq96o^ZD zDdyV)B%TAdCyF_b*{c3TfqbuF5BNjUKj!ogJ^ka2`rmA&S}KWSWFI)$yTOr^NLu_< zD+Bbxu=XCd6D_C}o>NfWcf@-rU%vo9-=djov@BQH$J7$_zO%Dlk2hyvE}NHMYz`NmfS)HJJq&bFd%|-I0CK>qv{G!Bo+_F2_>n|ETi`=1grF!J#j^`SZIH0@7=T zFM%-0DpY3Rvf_-=o{}U_t?`|vhJe`iX1QD`w<~-)=W`c-R|RN`8Nfo1Tu?wCoHXtL zmXn(KR?hE}{u^lx|8eQ-KNAa1oWn~Ft9@CehGRFSzd5*0wmz~P3+X7E`DW=v&6D-w zy^)MnQo6$HpfidvuA;4klo;yf&3(@{vh$8yR4k9`4zN4#S&0cP4d!+O@-*$9`&>}P_o^SumFZJ|ojUa1HCCWGkyUbx!( zViO<@r{^c5G(WrQaPyt#{Z6Bj`7g$v@C#DT@^p=nK8r%phJEzOYhiIA+NMf7AK_Js#iu+?Y4>_0te8Wa!a+Df$9A3*6y2r8KJph|6p| zA09owKYjoGd?9?pWr_mHA*JDTb72Yyj5c9<+C3l$*MGnHd0hs|@SWS}2GB_m=Mr$w zXS*IoE8P;cEGMQ(t^eiWd>Xe9=WOQ{RosfqpTTWqb*DJf3ITBv9bRktmoB9fb zK%A@JoUv*xGh}lPj?3NSgM%r{Qvg-K%3XqeB|Z(eJDh#@GgA^Yd69T2`5@~)wH8Ay zhlkHSc?NoB6O^>AS<^{a8)RvhTFP?o{H9k*>%JHE+!h=)rW5-^XDxQOwRIJffdq@< z;w>5MJLHF?NkTx1!04{xh@VPbPJl_3fv5hDi60M&Jfc5|tjwmG@|gZ)*;({RI8E1p z_rre(bg?JNP1*N2zZYg>p!F#wEYfy^)paV_O~{yo3+WpvhhXPmj~;?$@f#7c`QZ(m zVdh!ZleLGm;}?3bidKQc+6l7d;h=)sGErD%(Zy_q5KWKBpJj=V1$+~2@W)e5-pbuK zLg~F_7KFm_*aZ3+Et`f6wU3@a>2jr%jmMl}1EISn&x3QSA+2(w&_r=|W=j8l{n)By zfBU%$LTrsq_slFZ&$F5*bgbo?Ug*5TCYdgF)7bbMYpn@!&)ED%4;b5?i4q|Q=zNF_ z*+d|<9#sxNiShIC8fL^}_+-*Jumm7+XoXcmffCtfJY=xY`aX;P`O@yhsbQbQe7WZM z6Q7?jhddgr9sPmF!9hOU}kA`e$53(N=o}9%iXNx@)>RjT1X;y2$HX#m6 zFdfz#;n9Pe{YWgsqi--dj6A6jKwNs4*p|SYQTP6oXhka9Ys+xBSX3`dbA+VLO{)q^ z@zcUQGo}@_Ua0Qa;1_TPnwWa^&>8YJ(M5@Tm#~p?$NBAA=3Y+GYEWTUPEkgQy}j0{ z)~@b6AuZRFa_^4?G$v~6rRYl!P=8KH&GtFH)vIQC&9CvvUCEqq?$a|=;t3uvmn3)} zA81wwJ=~u^KLf}5OX4t~jBsTj&4S>Xj8sr7T&YxcyXrqdD#>5>=bTDOuS>a|J!4}# zK)kkk{UbCnPU>nVZ-nfk^R{5ir5P`Ey9OM_c+VOZAkE+@`Bs&Ow<{nfNbEQ2V-F0h z9`2%%>PVskfF`dhsi40imjaQM(ETgzKV-J;FrU+A92LQMOpgK?Zi3-?k$538rrZt@ zOt$D*VV^$->v6D(Q*{^5Xuu;~O-g5P9u=Lh&V6E<&g6kZ10RNg50!%;YpoLw^qZ)x zlil8rseJ{!%g7FELB>z0-#a|1~jvac@%a>*e9WaHH*J*@#rfpX9t*%AsQ;EV@yNe8(V3p>mZ zaU?$Bw;!pU7b1HhQWYH`8kwAz%RMA_0 z$sM85H*#I)wZfwA+{ygT;9*)}ell0550#%Vscq$V+F^txejy65F~YH0R0s z56X0DCh|00F}z}$M^3z&8T=W_au2hnT-~?&Zx>;Rv0)CQ%%o)`X=Ojtp-*IzIkz@c zOmd$$R}!{0m!{gq3cG!sWSAW`e;lxSGIm;%>U$O2rPO@WPFRi^d+2W0`8GSV%?r&7 zp#}P6UM>%8jKH1UE-KVL5nAVk-9cbjRO%io66C(0WE1Nf-9G(!fI-_Z_uf_I?M{RAmjcrHXNN~l z{1{k%G!9XF-u*~5k{5rO9Dz7YizG8m(@-dXEW_%{h6*PL<<@V?K`9$?2-m0kDUghJVYl6yJsYyYRP~tmrRX>B zK6!$>I=`JInc81tt`u1xn%kHj#rGWrHnB-|yB0?n-cvJ89@tY9l#>NJA-S@0U2lkv z{n7QPdwY$K|@&@e;Hy$O02wLyA z@y`daZ>MGvPJ0q}8sA~Yc2F0s9jANihql?$ZuD&nv&?(6ITk!~o>Des=1_5$zfM=W z@6+{iX$M{ON^^mHHt*f3%S{FZmHb3C72&t-V$w$;K5}YWYm4G9USzyax&C1dT(Ot_ zH`XxeXkz-=`HXVQ^`RQ_eYR2gZ z>7nl9w8n@y;}&Z=>-NI=ju_=77KHOcdEvby!$LlUz$BBD8vCf2nwji|xD1rtqF;3b z$^}$RNe%;D&_TH9bPY3hSQJ`!G9rO*W^=p=HqC3dYB{+8mn{!=0B?tJtk1}(EGa30$mnW&yGaX4z+B>9W+Y@ zi$+F<&s+X3Pzlq=6lUp%9f{9~-!en%6T~8c29MWn-9sXeZB`qC=!$9g9+usveZCZX z=5?Hc#q^!TQDgHT${B2iTlbYK!_G&gFK+HqUHFxHt$^?0@_)3zY8q#FhVFyqtxhYT zTBynE&{il7%pw0C0^Xmz=^qaF-zC`ZwAql_2$9K(!>T|MwpsVv4-X>LJn|MX2R|V# zc7XfNQDvY)4Uz__-QH*UEGqcAP^prWc0kIB8Z)~?}_H~05t5Wz~48KQUA28ESa zu9myKJw|stocBh%MwIRo;pR(52%_5evQ}&H_#^YQGpLX^jD#;twrc)MWN&)1_u9s= z^~eS();9oW4zpL#?w+6@(#` zG7BSPNN7Cr6OveqV7&I8u$jCIE1RJ}Ub{C?AXW#R{As1D`on8gA!d@wOEo9ze8AC~ zd{3|ULo&z@*_L>G`16CU0xo2G#|U$%X$E;`J>C#g<0r082XC%Kj>AAML|vsEB7bnI zIPLj-dI%nOXBi_mUpM%P(}pY2{aW7hd#vJJ-hwMJBJ)3PoN&%IRVFx*d7p86T}$um z7UB0668BIHaYQL4C2r^}qAB_vMgd6}Ed=I55a728co zhHA+`ifN zR;`EqW@-96e-UN;8ADph(c_B!8t7s#-DjIT%bM{s)H^a4!W_wL}UYymaOvzdWWL;2B07XU0LXjv~Nm%?Y(ioDt`aWn|@AP(@Ygt)qJ@NXvbj z#>6$UqZ#6^->yqaR?It#au$hK{lyXTV?9QKhm9Q_G|fCeLO|298L%?MEqanL#Jnl0 zA%`rk-^IR~D(#B}Yza_8exDUA%_`TLQ2A{d-H(*92dsM8LW2(AZ`?TtY3yvxJfdl5 z25XVLA7{M3J~#4V(&rv>&0gU3Ax6Mnt4{~S4x8D~Nkr+e*NUG*og4az>IV2CHMzeSuPpgef}XZ|5BH*i&;#e zW&Fp(BpUvQ6>Onqu}m!5g|1OdW^IB4JhL^h&BmXYmr3Wp7({Jf|L{s1HO_BVeO#cJ z>_&P_Y9_+d{m=^c*?^AgzPUc&2v*}&B7BA$l$_Tl|!|&>2ot-EqUUrRUB3zD#IAxZ=H<5+vGwJXBPJvu_ zv~D71?Vbr=CcpNBV?&jU<-UNqmWa7v%M`)-z@?<*0J#XZh-2wZ$H-EBDtCQ2 zDs9L7V&w-KF40{7T(>EOcwt9qojr<49GP|;d^P_?aoIa@E^~&HmEgsTsPk^&y4mG< zc@f%io=zbBNMtLCr*z@VcN%20WO(aBi1^R^yKJ;g;kVB=w*raj_o0c%6q~g8N3j0Y zkQ8TEFiTK6c!>hJLa4}e87uenQpjrD{5~gpcdOx}_u1Yn3ce0^niPFpGtGxj5;Pk1 zu8RW&G^|=F$1_%ocfP)rznZvv}r%L4i=+2WsJZagAT(gOSYWL+YP+}|$kZ$RrK(efeV0Bjqn(qC3C@i)_*}4+E@WKZ}w5F$9w% z2MXjOhPVifk%^$=lE7_5l1f1<&4%gwc?f2wB*nq{!X{wqpihC6&aZHiLmV$7=RBY| z-d2!+lLCU*MJoUX1(78V+%3GALxG%^?1SwF|GJHN_yykNaL}2QpVkZ|R6q zq#t1Tvq*wH0tIICD_45RFJTuKe=jclsZN2w&Vdqxs5(1^ltOe}pY;85uoEzu(6bw6&{0e^|tz} z2mA-k+h2f`e`IU&KdAuof8E(XZx!-=ec`UO4ORiHQ`4F)MU5HlLJ}JToe+({QbHs- zEF6dKs~naAdP?69suJb-WT6AaJg#hEk#Ziwpt1iU@96r6Cuc)k< z^$ly+W5#w*aOX9}NWMUr1&ZC+8swqVwPZh8cK*0`J{K_(|!Cl zob%a^nPVoRDUrCIBw^31`1OPc+_8bJvS^+>^EK@!`k&$75+0|Lf)Iw@J}3n4FtmL* zsRyG8`nnFJMwmK$V9pvG(3D`bf7w0L5LwvLw;RCz^7^`Pob6F#MY)K5lQy&9Q=g%& zj(9nZVCFPA4cUF+A29qBGTEkUwxSql1$PXffa#K}k^)4H=3)9bVPjn)-Y-5^woXGs z)TE4yEHokN9h*urb*q;HNQaZ;hZKmx4!IoA6xsQrF1`CBY)gf%Hr{Sc&X<4CbShn0 z*9WPJ1_(e(Gm3OLOn!KHQ`!qD5vt*37i#WEJXTC?q=#BNNDkp7rM%uNlwIJ%0$^Qz zIBlS10#6Pt2OM9`*sZ~mz`|7qH1TZm$4mvnN-frXjjscHEpE@~fC4Fu+28KaJDa4b zM-58GE>lOl2WI-WhI`M*YrO&BWS_C#Ouw_X2&c=snHuG6q^kni0aJA{q4H-R7mVgV z>hrN**5O{GW-0}5 zM6{1*OK+Zd)PCw6wm6%fQ+YqOXAj^z>{x$!f$8@u)$cK41-VW{@ibC?{v6`z;N@9V zTCKXemc!cA%T+iWD#Wg(FK7xYDbi=4t&A`BCHPM>3etT||rrASy3mOl+Q zmm-dvPrmmRBTE{&J6}+duhw%x{A$+ILR}8)%AZtIQx=K?a85DDS2xJsN32I;tzDhl z)p+vvhdsb34;WEH$IkDwM4`yu^MrN-YxJ!#8MVHZtPH0nG*Q^RHPb|%F&){QJ8u!4 zpZlrjkm0^lES2Dma{`#eZp7C#V&(Xjy2cq!0LD6}nSoSBTeaJ(kK`>!oF+dYTg53Q z*pdAJj@dAt>AMlk%C|b-b_Ts;)|s?0)l|{_W@55$-x=voSj4ZR4h6SxGS8tx4O#Rs zyI>0BWpK~A5D9>@7|irI~C79}nam1Yr9Ru+xhz+6xNR^Ji!r7!>;jH>32xl2l z1b>I0$o>K3wgD**)r=%mAh)H#+t)!jTO9_%*=7*VE_joTvGdG;HHv%=nJl|+Lbezt zi_ZUh31NL-gTYOllCmI#l_5lEfWq`Qfzb9n*{TwRvwgq9+1zyy&OYw}RAoY7xO=dl zh2$GOvoOF4_A?FHzY7Kh)-W(8m_>|{w;Dmr{--C#^m82+gHRcq8n#Wqp-mr*3BN}4g_sF5fH%k z#*I##laZ-?b74_#_`FV$?hWh5<;FB$zq%!~yPdB6#fZxFj*vgkn;$1FsTMgj=T1}i zH;hv)!#*1qr?pB2#ko|Z(=8F{Bpt$z1&94HY=JcS&1%^~T{pPQl^CwAw< zWAnI0SO47ysT?NK#@;=rlqQsmNplJ0h7e5tn3r@_Xc7Rvg39}V2|%A$gaW*Aww{;P z^w>_>4vf7vD!oso1hr{d?#!q@{-R#WX!|Fh z6ex}lAT62TnDOK^(Mohn72~@1hufnq>$j_>*DneCyq2suHOP*V(Qyfkp3PT2UO!`9 z95rLIrlIX4+}mb6ijjkN z<<$VEZX?*h*%r6dOy_quI`qbbDG=T2GdEP;xPL(+N1I7*P5E>JMV~l;X+eu24^q& zMf{Qy2p2dh`ORKe%5ixzBws97UQNqAAP&h-fp|CYTuPN!ySgNUXF~EnL$GMEQ6Nyn zCgDpEG%HAAl2qe`VP5G;@f1tsTDm6ESLU|5Zf66HTuhxAX0}9L@n`=z)^+sDG|-XO z=?iruo^nj@i#%L#21an?M~I&J#!bN=m%)`sJTqq zG8aFRPkKHDokgvKo;KhgZb0=<81Rj{uIal`g~K1V7OhW>Mt9yLyml|>tXzv>3=U-J zldA4rKL7fBs*@3fy~{CU;!<-D36Ed7IN_(fxq}2ckyy_wlh?*>VclWber^or^5Gvx z&&(Cyi$(e?4~xuOMviaz>ynrhV6Cw4^Z~oWjw^(N%E;BQj3W1D>6|Mg>tw{#?(?1wMNi^Or644h^Gd16Fcfo za|U3;n6_x~`lcrqk|JhZ0_WF0e0m~lwendhsE726(#nOllu&O(DaZg7B;Q?=QYdYj zGstL3Dz)QCSaRp8X?;&J9v98g(r?-B^;+0D%!vl~@kPUMkof~=%t1#bF@gfQq2_2L zn8}mw)Yy0Cz`V{@HLfU^Si&_aK(yx%w996+MW&yWJ zSVmi56;ju1WT%8p@|3g|mVEi3?D6!Jw`7ZBOJmV0&5FXV06!Pgxd5hIVsGfthsF%W z+Xhc)V(dGLcTs}-`_w5~fWceD=q*3k(2);RIcoM^9jR%|%m9AgMsDl2SiQg8npas0 zKG5be$@C*bFWGK+{v75Ts+g?4J>7eeR93y2J-?$nvb`=7H$TGc6C?3UobsL6I}z** zXY{DwzKuC{;}V4FsoaNRg%gf3e@=pQ`@#DegZV5s2Vp5wGw4(Y_tvcS%Vn41U&PW| zCRf+wnCr^$nyGH*o6uCXA`FF zAZUL^LSD(Ab&IQfytTqBj>$G@wpSm`pN0Dj6#t!eXn}ZqB`NQ+IQfALwvuF|U^o1I zbJJuO>>i+^Y@c`Zh1>?)|A+gZ{Z|Jgt%D(WBhfJfri_$T15>-oj(~gE9_QS{C+fk( ztbzFW4g-3LS|^cmHE z%U-^NOmEX9Os=FQhV(2mD}6l*#*$rYJ#4>yex7>iO`w;64>QB<1j}2wDOMJD#@H?- zi%aNT7mJ$FI0rtA5)q$4dcFczMh@|Yx!W^VDutP8dm*KFH>48Q=B$stK6g5Ki}{Lp zRCgYVYx>j7RByMeI&b++X92m6JJQb0_PUKk=!I{XtJTIle*zT$9l5wl6(V{iEhQuc z;hs06IG?VzRMIUvLVBL3wfp1Vn%wn+*I%u*FFq;Y#=9+;X`G`oPgC>$9v~jileBfD zmK`#c?xYZquuMmQF>T5>AnqW40XqsH2R^uv`p2_+!%Q1ZDG-64{{6~bY}A(v=2nwV zto`?|lwHzD+%PT5xjeqGjNQ#;onfLtxWl4ISd-^zu>Hsg*dRTUSa=`|<`*KdWcyDc zB?Z>s_^n6EYEPXuG3KzbM4zzz$Rbw!()%%$NTP{Zfa;32Y&T7W(9<*&uXj&`0OT?) zUTpB+nA}qcSJyXFc36BvQx)}BB>xTY6%k2CsZS& zko}cJ88BM}Cz#tsnvAkG4Fe{XeNuCdei!;CjT%iwhmw1Ojz6nkB3qYk-;)WKa-8ME zWFkVCm5=iK+DWxro6mlb#&$^Hbrt!A0HJaPY;d!-N4`PS$U*=Cz*D&-&LqE0BYxtT zu~}cCefJ>zjZUpdI&X613Rd3#M*xII*E1D2onGsIT*{*uZ=J+9$Ka$Mri5chTN zc-+6!*MHHD9+)~3$1nmT-U+iuF1o*7LAoM?kR?gvjK20C%o{zsVA16Li+{Yx`d=E2 zgV>X`gT!u%A!>#lZYR9{M9L{}ShuOsQGtzrzl~Tv{@%yw&DFS-r|i`8ETCVbMZj)N z*2-vrr#FB-0SY7?NsJE~9Q=Og?Y!xTRB>>y?Jesb8KX@3kCD?22KP5odV5;25YW2XKrU#(pEwluMwrA zA2m$Lq(8V&r!KUsF)-2KE%m8aJ%g7wDI)8?E#Gb_j%QW_OnNUru&KI z7h}FKIEy`c5o~bF0^gYO#+_GhC|KGmNy__0LS@g?c$R`JV@BT3F9B!)BGi%SLA>Jb z&OW@1PN<;UZ(umplP$C8Vt)9BXS{ASyo9%47hil>G23;GGfhTD8~GI)DM5Mw(4Qr` z;=ZAf+vtZlXe?S_2PH;!1PppFrCHA18nqnqyl(DWexKMUI+6co=4_Js?rw*^x36I3 zRLYmVGdwO|-gQ7nRfy^)EktP@KDCP|J^TPse9joZI8Z%-|J(EBoO_>uN>$s=w?iNY zr`XZyk31638ZdrIwP3>g0++b zOia;4cwf{wQru(zPDqz4kGkznSdGe3(3#WSl8d|`2h$#6*Rz0qvAV0bFQEFsVNZ#A4dzZU2H>eo> zTrOIlVRNgNaLawxz40FRrKUq%+Btn$w?%2;bBE$qPR~Vu;W^OM#b)f;%>AmN?8Kf- zKPiseQ(Vn3nOb^U6#e% zkt)}ME2{nWfzCrW8D9BcXncrO=oH@N*J{~8`SpI6iu$_CB2{$`rV^5+IElMfoHn;U zNC@-MhLc`R$#tBsh);d8Vehm&D5a5;?IEH!q@q-!p!a3~NRc`nf%ql9MDw)tw~+-% z!i3Khdx(YbPPZA?CoK1E?#OejESEF*otn8iubVe7unMoqzHDy0`Q=YM z6n2m708A40Z#nbl;Eg!;b(OGnwP%kw2s+zjkGakEnPAyB_N z-n0J=z4PDNmad=GP1~6s^l%t|uww)@MvZ?~^Z=IX>z`Z>AF?iV(Pjr5BK2Pt>U-7g z`;tmdf!=J}89%QPb{C~ZNV>-FNEle(4ts!jJLp%ej_ryFY7Qt3mC0oi^dzAe8)h*sMpPeY$b}Pe z%bs9cWpo|Dv2N}*`=XWuXDU?lG~vyY3FX%mh|qgn`p$OvqAIq9c$B+f)cB~XJ21B2 zaY&8K2O&V{i(EDg{ywgv2D|bVCx?*g&DT@eu9UB;4X2T&iv~si4}0$!)KnX`i=rSl zq*?&!UFjVp5TtjccaYwsO9>^h&|B!;L~HV$ zzFF!eTG*&-3LkAY$^qXmF8xL? zIH%54Z&@|y*;K;ZY&MYlU~U&4cF`riNAkNchcn2~)C3H4&^$Zq4LTdR6r78!26&x9 zkPXc^2VCk`&)OYHarj2L?bw8?qy}OQcAMLW624khcTh=?w<++i2HOpSsqMIqFqccl=-tNK0HeTsH#Up{; z3K7nqyky~)I{o!?ULSaGres`YErc^Z__{$38MzONrHzvtjNcic7C6=@5!EZ{>%}N< zkc?ur7p_wno@i)iqK7L|9}SBk?2=1EvvC0SBm=140xytlL)h^4E8bf)%m8NDjL@w> zM2FV0+K`zw)Mbt#c!yN%ZS%Jm*pN{_AN8Jm1*vM60PQUqSNIaDVenesOe#(@xJT zx$hBD{b!WeB*Kaq2S7>O;#|? z@Y0&XSVi8)OCIUlK2CQOxvZl6bf?61v`rp}n1Xhib#?zvRiJS0_h3VY42l1cP2Z~8 z3!Py%1qp@m$ZrnGAzyOv2#${v|AfN<9z042CFD4B0G2?BchnIg{Hivh4w^X+?Ix#-2wpJErL#}>xngB=fWNWAmtD$vg; z0@^`E*|;D=!JSat;ZOlh+Nt5l4`Js<4=%e1!;Y_C5rVDU^ai<&~d=3S6WPaNd66Y z_HkID0|1!?aKw4+c~2(J-;OO_?8ceTb=CTL?iNNFAFPTlFRD}N_RD2M@7^mjIF+xT z+eii}(M_<)vq#qT8-wY!|K@EjnN+;mqWa0rF3|6y7J1zS6|n%SB#aTj*v@~;ZmXKa zd0c2w$3&T?&>}KdN-@-M)^ES$je4v_!Qvu>S6!RcC`sT-{Pm!`JX8d{FRtogc&HSY$w z&a62+%i@fZ#yCExt-mM{&w9l_Ww1PS@%;K}y^i=fKy;C-2859fCuj%*ha-k# z4srkq0G1!Q;TRB9ZMA(ob}uU^9plSV2|)7O3%b z@a2;;llaAqmMg!1y~8+YB`R91AL{k?{rwTpGsoQiFi~1#K-C#0zPjmhx!mgB__^Zu z3%kU_AN!m3aTQ+one}51DyvqPcG}zuDRQk-OMLU?m5IE?_6m{Dc&pfrTm zMnYCRSrGs8VcM)sZaSCWWEh9LP@q9JuD3nC?T}@S+@!&r<$$K!2C%Xjk;T{ul+fCa z^~D`Yo3?ZjVSWMM9CDCH*q05CVu2o!85QIC=h3f^u;{e_u^#ypKwVjc-s8-^FV?Ep zGuW6SV565u0j;+|>pd}hEfKqXfgNWH!&z({B(FN*&x)iBxd~BxsVk>zVqW(bUGoa8 zF9HgaD!JjA&n5#a_p?TLoRoR4>eEQ7O&&_!Ji8h$nasfGgzS3+(gA3;jS!#jdT${?Cro%2m{ zpUmt-TE4tK;H49kcodk9;P`UyK-?l13XuB8wMp8*Z?$dIN7N(G-*Q5Jaf-|AiHOFU zS>2~=A~k$BLC!hfhmV~9SjC=KFCSaPu0s8mAqez_1~GebgV;OE8T#h$xWwpum)T4y zIn2V?G;=St^zcpw0D!CS0DFrYl*i9=_WoNlj12!9LzsyXc3@iXmV?6t;E`>AOWeEC z3pBSV9u$-z3t&>gLomsXIY+Ut(-}BAzhX~`ST~IssbEjel$q@NkVWqTpFNWo&L124 z(vI2xa4&YhRx{xj=i z86aDLsuN3@fPT*GLGRS1qci`x65S9S) zG|iTME+Kl=CU>adJ8Jf&pA_LqM0Q7}?%d15ufigqQigfF1@5r(KL1eF^E_}z<2oCt zb*qmmEg9{RM31doHjOUnw6pU?cbhN_C2>@4XXJCG5Y%LnJ86u^9uD;RG$ zFT@ZZGz4|WXBW5HpdNWXA-#*J?Df&MdG*KN054jq&Q^VN_R%8g?8`=6m2`;gU9XhX z*nX08XAA$qR*zy?u%@%qZwu&vAJ=FTQj*{|lCeDri5q?579*Q?dgBBss#>wq3?VQsr38@5smf_vi$Ec^(Vc9zpq@quuV~O$mgKO ze+g;Fz=R?8iZTuogg8CiZ|m`5zfupJSE&D@@M>|`vT)5W$tO4Y@?+?wtHrme#ZR@A zqcpaIrKnP9IBqI_qc8Uu*344RoTN54eCl$2LMa5W-z~)V#CGDz42p-igEbU{7+Xb_ zg<|adMi&oIt{+v)Cs^l7?_0l2U%6`{y=*e{Xgy@0cRUcd};-!M9B!Pc)(Xa^AR2lx(08gC|L0Rk!E&<4wWkD}+8blrq zbM%rJ$AQGqM%EoIx-SZ6tl!V*hLYWQU-~vH88QJY@tL@YXWw)nZeTGMn1QUC#ud#` zd;PkWuQNhTVVHtp%^ckA5C-0kc^qB8u_n`l@W_S-A|^M{@gz{%>oWrtzK-qvGx-8N z@sUU5(+s)&ViN2gYeRy>T_UNS_!WmuKLHDPh!NKCGkAYZSAqi}yk086FmOsJ_el)? zktj9N>C>(uZ@3XTrLQWtNvgYvu*@wqMdqU@x#KsQ2^pyAe(t#pXdZR&>(U9D;T{vj zu8I`*sX-vwk;>)Y!Ha-_IqpHWo)T~CxLi=@)@_F|m=wW{UBSCS{iAk3x!}%|U{bAw z_Txp*oP~u@Nd^Cu*7Bo9S%$k0axp_xV`Uk53bG_=F%k z$Skz#g2xuV^y49ftZJ>dE}ZWDjglGS$!_gW33z$j&$Q%vtwm8nqUe8mq8|(g*V0~d zq{;h6w)q`%L_R~<5_^d#d|XaB9+?%1-vShC2uiaCzL5*1ULm=QFPvrrk?*!T;I}T6 z&34yl!X1Yr83Q&?`V$(ytUquYpB4DIRd?VFKdb*0i)$ul=C#Yq}U%iRB2g(G1kr9O4ayuZ?$W@BO9U@N(AHMaBsDk*J zHqQC1x8C~fm|-LDsty(U)LSt5c8$-GgCbrE!gg`s#CKD?bHETL+S(nL~>>TqMM;yxLD9{eaJxx~fyxyUA$?`LrZwJjEM8N=IG*0NkhjB}3=bZU0-N13M% z6>4uTMsT5cz8-uMt`-L%BX#w@$ zHeykJB#}q%>_j7&{3=WTWox=~Iln{M#D+6HS4x_uB3jQ?)BFA%=KD{mwM3;!#vTQj zPqKv_Un^Eg_N3<>jx_IH(x;CE(i(BkesZyBMx|(c_vH>O`P-b*#rb*YBR$9nByq?Z zwUK^Ke3WX(<0>MT$#j;AnrA6HUTckg0+x)NAw+i1;LBAKmo!zoMaPgLeNu}IS9=A$ zLZU~4%9sN-aZ=42fxh&`fo!0<{j6ss{|l(1^YPMHE#9Q3*-@3yvvYn5@87uOZ?Rmn z^2#wU$SH(SmXtem=iZn7Gc7bZMwQ6Kld8sRWl8&#GTQAKM-sIMN79X&NB_~6ss&Uk zfYcDh1x#-M%Sf>gt&JYat8e;ALXc{2Z6|~E?V|2*g}Jx2HquEG_~dwKUi4lp)5myh z!D*}ci2JQA9XOg?k$wKu-TA$VwOj@p+wSih8M1gp{P6a$mg{q`8+-Ye?=E*p9}O?u z`ENIZ+u0WeNC%>x|84S9FBpLDU^!93;76tNumNxE9f_WiW~9SBvCn-IF1=eI-PBUP z+gR_l7?K&}bnii^Qp@+Lil@UJ9=97zy`x%y3D_Z8SHHgd+8kyqt@4|p`S0!a&t__e zGf69W~3}Z>5f!*IcL7 z8qQ(TOo}&3_(0u%Mq=oi>skt~rUnJ}n`!jMypg?k_%Nbntz;JWao~R`dSe0GGc+As zE4;hvwIKD*2Dhd=)s%F}h9!DZge%n5cX;!(8=9M&_`Lij-4PR4k^J#hlbG_cbDxqX zM~d2|ig7NLBj>c6DMcuMqV!j*aQ6&F@ytLHJ(pZEI{e%1uReokiZr)69LABzf5>v6 zD)=IY+=7*Xyi=MdVuTOK?kgnSaP^rXtHQ z4`7lIkMi@Rq42(#KQXmGcq%f~rRP(smwvAG+^y!y+YD1tgi^{se=W9g*LnCmWlFkn z?MM5}9Vrhx6RR}(b(x#XmfZ2T8XjJJxLG3bgZ^ZVmUCDBzIO0sVCV?KFOZ(SV*nT*54ILad<7!ze?rg7FY>`VMMWZ$q~9%zWKBXaPE#$!d zAWjX5+WQiA??!A6XD)vhK_^KYKn_3+^rrOCfaMuxABK;>Cs2TjBw=Jtk@S+FpiUf} zk4(a}vvUwcRq*;*Ps$MR;-5Q5c8{9t+f#m-1WA43ul&}si2kM!Sli&tJ{Z<02h{s` z!sj2|Q1%-xA+Dq()yo9W>a{foyhcYI&&JB*&Ctt<-fy~$a#Np0@8I5*YO9_^Zi zCsj>4ifyDCk}YbD8ojzv#&Hn0W8IHlTdxx3Tymq-6Np%^mDmY= zlu;2hA%J!0`nz|8%wCGPWmlf692U#hW_zmZwgbXbJg>Aq5MA+Zud8ez-lV`xeEaaE z?F1H(GpZ#F?M;jd%RJOCYn%RklETIsG89jdhn?BXYQ0-~#jZZ(e%Ow5j0;o68|Kgi14>oZI&K0r*J= zvj(6@Zv|B+_!-XePu8F$PRAY&DS6C)Dh(@bo;pQI8u~%i(hsV6q!Zfj1u9@h8Ur-J z9@}Diwi3EzX=}5TSDq|&J&WJLD0|GfiVbey8^#qHJTB%l`bBULpQ^$@afu ztAsv7!ob?d8lm411k8_H!p#7uD0?-Gm^WoH1_p>>N>=r6^%sPLg>NeAn&%oPn4__C z8{JP8P!h`%hbpZLd(vND5;!YgS5l?lGrKBbAeNf(j}{uEf& z8WQPeI;eM%px_?V38&`p$`Tk*$~KqSIv1sbU+}q zruetj(IG7z&GnW}t>Pm-EEUt-5&q}rKbxW17#is=D8xBLMahdogW*h=FjTKc6i8tDIq`7ETT0Y zxZ9@Ia>k@*vWbggdU}q-ln=AYxZD)Y*yzLbW%mqk%s4Y}=r9aAiOz9~Qt7A#(WXu% zEaI5Vl33jV9t`dbUp<6EtQB-Q&V#Xxp8#oj0P7w}*c!Pxk@gZL<;i68EEQfmRI^gq>cmzGv95OK6^{gTF?_g53Xnsdi z1cnpT-D7NW3aj*9HsFuTfq36H=0>EdB z@&n@j5&A*E?9dLgwe<Cn$*7F*~HC$TQ)x4IVd_KbdjAo7bD-DO?sl$7y-a-cwV<@~+kehZYENOy6 zm2%ARPFqWQGxy3}JWhY6;apB1eYM=_%92EY0e!p}S4YvPy!bfT2FJk2!DVu}kdHMm zYP?JH(JU-jG~jQBJc=C53vh$5GT_H3EG_XnAmHnMed`4>18O}VITaKX%A49y3EAzR z+{-oEeG)CBAK+a!J|9#1j&AdokXbgtZqVq;1d$^RdK3rL+RG5kcBx$|kPjeB%h3z?!mdu5m(bA%Ffl;ILSS z0%D6RR&?wwXDrsV0pDMF_oA!J@-dfg>z4Qt#c{$pJ*KR_$=ZViQ-7Z&=MU(5`CBQ) z-yBsN$(JaC{Jsh9VU0!URu#Q$>x^`TbjZ7+Ic^Q=IYxrJpFasoE?H%2A#MSaP|ArL zhg*ll4Sq!AI>1Tv1a`>qAqcAHQH?>4OpLM%{e1dyFQ+Xh8c|lQTd7tZ5VU)|&hc(7 z-`D-D*w)GW|7k3s55{tW`XVqs*GW;wm`+dn31d7z5JyWZ8qh0Br(({u+H=&dRO%?C zQTn*PkyChyj+kuoIoXF=|<`4I*k zM&@EHU)jZ+B&)ogon&Zn%(E8$t7~{L3T2~wdZ9V?1K@cj@4FNEFNthVF%CmWpusBz za6^Zebn)OV!_1C>kKPVx4TLzWnI`?)h8=GXEtOntf-08PrKsy|FC5xW^B!y*;XeLQ z5M|L|b-l7PlGxF@A+OWkTDF^uPsN6ePo*EdtnVDRP3Nyn4j71LJ7!;JiPOx7M#&a| zegcQ0yb>Y{^fHR{0eHbXOdA116h-u7Ht91fjxrWV}{k#Iq}I0v0N%Wex)m4 z(&>-BOE)>EPQ6~lxLiwOjr*@g2UPp=w9}gd@;{F$-qRc~Az z64;BF?K=B9Q)(%#~*5`u<#S=kL&ygA>C%27;*sJR#XK{i_Rmy{{s9OPW(nJ zC)VK>wva`{214KFn4}?|J^N(IM`Tx5*x<-&Wobp*hxuVv4wqS{ulr{JFlK%!;|Y7T zld_*-#mOO)ko;vc{Ujy!=&tff65V^P)Bgla);wp+lttLh7m7YA8>pgzU#v(mC(iljTHuf=dy zS6@+++DtT09ZPn-<7Rv%Zv@WB4`mF4^4|Utpof3>`zZ&r%wD;`I~m4;(0T)1PwO$XMm$1X6Ssup9P0Lw> zeDe}=oH!UbPO0i0?TGHbU|_eD3NHF6D&dPPh^8>6(yt{zWG@q?zA-Q$5S5RVLULdRmj1&sHPBNVYoxWd!Bn^@DiLuRd!l29u=8@8sLAAhMDAnahr1Q?n|bIq&?5 z9UG%1imJX5Q-OP&+H|~*LwC(THt}TqiQIIp>D3me`<_NVtzi{VaKIwY zmfn>4xWQwgn~T}@m1(Np7yd35x_1D%%lvHOxyUOTZ{pb$SQ0GVv9h%`I3Z%ci%=uh z;_t^rRg?UnZl05J?T9|N)M>D&XJ~TDoug++NI#Ny-H%c%#5a)u=O@qa~J? zonb^M#>kYqw7|uclg?$*S-zhvpP9T9=a6%BU3r)x5n`5aG?M^ZeZDIh&D8wFC5S)O0-$S4o+dmS=zK60Tq z*8a}7S4sIWbI{?1YIN|aqNd3t7|Y8$+jR4#-xzX4;SQH>zKw2OC$VGR_rS45M9*j} zfc>3MhK1RCcgqs0&>Kx?8H1H;|8M14Fc27j7Nvlv2c`kt#vLr-X-2yo@F6X-TbIRO z+HvD=L*Ltc`a0LdQK#6nT3geR5wreXg=2pT{9k`@8tV`Q~Dcq zz!xAdhS>4xYlPaSwTriz(kqphqpzs18_F0%KsdTcW{*KXO=oH~zlZmQ{M7gC{czZ=fi3VB>|HJBlF)#? zL$0xaP9j=hS9He;8od01J2lc2Lv5H2^0IY(_-;TXDc*3Xc}f2)BmbU!^~#`}GutB_ zjouE0HKFfxALJ6&H)KSNgZ%rS>jb9pzbWJHVN^4MCur2EMh~CISFfY_-eQp>4sxCa zqQouDjL1TQ9|k;@i{nQSlWLazDrgxo1(=J^He} z-6ZVz%T@6(_f)xQIkcLA<0&C<0@4mlR?T6pNkFIGdW+4IO#rjx%Ju{hog^zEDI?4E1tVTAsW@K)#8dOqdk zz&?7x_%V<`K{F-~!*KH9@Zn*QViX z_gCFoeN1%o1{o1g<+HAZ*e-bETn0)9GAI~Fgs5BuRwh_nZ?kMP9gVqnOx&D_BoM3!l0a_obE|gDP{xq(y<)FRuO81< zT~{kN_I1in4F+xU}LX%z9%W`d0_2lVZW^G;dA7n`}6!X(9d|InthF4c<9 z>hvb*XjH;@^)X;;a2Y?n4=B3> zJ1q#?NiRG05)4!isG1@IM)PE0%W1 z_-*Jm>9exnMQ08lJNDfqQ5*W64LsN%SqOS!+)G1YSL^NpiSPIuY+0+{iDtz9ZD_}tAK{z2z3~*k8*gHAl}7_m?3%nHrwRwz|)x9l$M<;e^{7Aw3QbN%5yny7~#;rc*+qTfHZwYMnf%;mYtU#DHd~u z4PpzTjSeBRB1`WR|I&FGm`vpz|AJStH>~U)jL>~3M~E8-XT%WuFv9L*4Frp^E_WQT z!eDWLo$zVJvp}Re!2S7RO{n-&@O(@g*RWd(uN%d%qDt?Uj=Kobut0?iBA%cd+Zxtd zM(=D+29i~saXFfNKgYpcIjbW3oduERyTPQwuznhz!bE#>$L`T-j`7$A5`n@+ZzBm` zP$H;fsi`1v1F91|I|S6dH`hbr&YUmK0h!+aeD*8hUjr8;d#*|f93lDp;i_1gV6r1IBo_OQ`1TX8EISH*5iK@4TEhn!;n!t%`x8c}6G{h{p zv+neIUo2zb5mr9p9L;TSW)ZQ}50gY;?-Ku3K)t+?MPOhM2tKVXj<``<7%3_!i;8l66HjklNlF{2J0uO**hdG-bi-yrb=8cmksnd=uONzh2IQH zW7+!JSq0IPI2t#)+|<00jgNbhM&gqB1=@HR|6`wz_zE~Fw(RL$p~QLo=>o>QmH@|y zjw>kM>Da3F_UE$Gul960+j~%q&Yafzc(GV&KGmB*5l|%vHgXH=x7OYfPi17%8aPi@ zTW5U84;dVm76TLN~V$Q=Ktf)s_TYv^p8l^*7~0^uupErX_Y-Jq}IB5mp9OQ zhJd7c<17@=&n-}p<(eoSpJk{L2JschE2LO85E@`B5pmS)E!uQ~n5$^NKKwD4sHo2T zeAOIyh%0a*rkZ?c^cP@Qg-9Tg8t$aV&~^bzS=%`Ur{hSsbwIT{a-7+wk|kQb6*)sA zfv>%K$}o_Fk#M_eOrh(iruRXuC7yIuv+99{Qij(deVB4|-TH~zo9oAn{pK=?JXcPJ zJ1LVjzA614F0^L?oEfj{rZyOqX*|y`_9PVR_fA?=dYAb{4$MMVOIq-@?oA=ai|LDv zlsew+>@9<<*;0mvECrmUh~vv`{tmaHOwKclgr51`KW+DmrkPQr1D-cF$Um{DygtWQ zEsec_jSIuZA8iA}gMm5))B`7zjY*o2bAXhawRUyl&5LiQ?(J4zwc2TZ@zJxY*}RTN zM^!+I=ke9Mb~O@n9{mUnI8}7%^*Q;q`#Oh8>9(3Xn7KspfhxoYZf6cPSmBLJv93lv zINjRZ<^zH*DF8e)&yG*L@FSvYkxl&gwd_wPl_z7Wwux&eE;y;&4Evs73h1YaVj=n` z^=!WK0z9-jo2S#nsp!{YS(HjlY8NF!M#*X)!Wnu-vKbhhes6ESoGFT7liy6gp3da{ zC=VH3)yLWzce4r|2pgw^`as6-JOF|s1Pq^t@FXr16DALZMJ#ZQgb4kqLuswXp?kl5 zfnt!~AdZC>PNyBY^xi70tKCY?7(ytw0@1TOu=gc-uM;q z-&Bp|&WZ|T$ZC=J6&=O#upH!GNUg_bpV0s6vk3_T+A?bGS4xvB)!( zv2_Dvl2tbx{f!~T*0m>6qINy6ZR6pQE%jVay8HkiXR6b=;a&ZyguTP$IPnW$dm%H} zvmJ`qRKG4r!^RB>gJU*$tnKWF#0g#V$;LGyPxJeA;u)3Yp3C#PaUs4Y9odiiuBJ-M zUwuZ)p*ia{BztoFEPm@D8e}_KB@@LVhmnw^c=t+5u%>DhZVjmaj{(g)xh|mcQp6;R z@f)KdjMa{wTRG?gMc&3$`i%lJeLzw$s!8> zhw$hOq%};-9VQ!Vr97+`a)Oth!iour-B`W(7q>f{B6M2|m^MTo3f4*mJ}#yE z@iwuHO$+xR1122V?z$xkbc-MF0EMb~1bFJD9oM{q<-PbTMKxaX3dS}2=FVSv&^0ah zApC&85ok;?v}nTvgH{x3N8qCm)9wruoG8B*9TpVwthSVsS=fGj&DFt7V@j84O&sSL z4Zmwh)jqJp0v}j65cv<7TG#Qg1N-Zn%p_03+d<>oqT?&KSQ+%q*Zl~!A8zvDX1}$n zd7lL0cZB+4pkM6CLLTUa42I$QnvGiUaWltz?2V8nl3Q5Fr~phZ3d~k_z6>k<^EV>N zd(YDM_W@U1V|#*YQ(H`L`q0C~>XJ&%thdjeu89_DXwlM$pM9N5lhWjmhK(zb)RstU zP$L_t$;#d_0X?m#YTem3TlVF?(F9vVl;Xy>Km8HuY7BW}wzx76K|O?}rbr*;@Lw}4`uJOgkBE=;tv?>Rs*kVZGzKhJbevcS&ut1@{nm3zre9fp zEF0a*C;QJYv@Q(hqOM5WuF0(ce)}%T6S8LkU~*-#KyN3uh0uZ#9bS|7SoOw%#0l;O zxPz1zQcHurzQ#V1dimG-`nuH|brW2a5)}dxs=PBl4zVzm6o{Xua_Hluiv|1#N&&-F z6qA4MpZd+u;Df|i93KNfT~zfo2KR~7S1dcTMu(M#cDBV~2Z$S@MKE!gL`NB6il9hX zk09J8RBv@sV}}=3osv}Q@vI+0#~oo=4faS@Cm4>Zl`DI<0RlzHNih_9jrOG+(H(j@JSbI$R-po z$%DXvhno=rB5P4B&Mg+y29s$Vlb9wgn9poIUNFD-9OK`;h~djDs^j$MN`ISbOMBaO zXCjl2T}>kD*~JItF6zkghwI1kdA5cI%)i1KkNOH11dNiqGI(3)md;)0!Q2`uCWb>a z!?oiyoXdL!K#hmE>Gp|$|LkR??p{{yVeOYARejqsZ^(3}@xYt6r(O2Zs!kUAwI*{R z#d{8Ac*R_X-wwK%ZdkTA>}$U1iwk9M@$@{N-&cz5T+Lm=7jCSRe1K72z;-W6A_5L4 z`;s7xMGey&KR7oe`gq={J&)T(I$X4r1l<`Btqz|jl|_k2oj&*!)$o8%MBX|3l8F-x zqlm5^-mNVU%Ktd=Yp|d_xrBt^lRauTBQ6osaVV_p7Jx$80vBKqg1Sk%MrDx1ku%vv zw=&1R-%W!2mEvO*6|5ei_cW>+$bB1&$#rp1WJ#-qJsVMwuF|u)l-e zU7!kNwrzvxoPQ%b1wKs!_=2jjzZp(h{}pfr>eqb0`-DJXLv0Vv;Y3LiJ$@j!1AAIq zc^SIL{@%B5VNNdm$p5r*V75A7?|Yk@lKA(^@5oCXH#6ei04O+0seKb-Ve`P{bO#Th zyv*XRorRYOen#n=FaLM|sQqjJPrz6dMK%E@!iG>;2^hmLf`wtOS_83r=7sQSlJ^QT z+R)ezY&z}xlcOWWGB>G^#z2KF*-UQX#>Cw%p}=A>iVX`U|1~O9iFk0otXL~+b!<>k zpc5lTH2PR=g%QzpJ{ZLQeo&icaDvb;Y=Og0K%I!2#Gk~KIh4{rWD1deWqm-zbKF%@ zZtc5w31ru8t*a!`3~~?e}2P`k4lIR>WBw z9bE|rLR)#51KD+P;udSdNDu9h^{yR1MJaeC9$Dao4b}%97o1KFH z&GimPW=<~IabHQ}tl~$G1t6kTx5M1ghQPwRV+S3)0cBuFzf7WUF*=7>#YC5bi)Ho zH|R^0J`t(!@T>{Xj={9TBqP7OODyk%+s*^$28YRgoP(Zc23J0oN*XkdC`UY3H`=(K zDn4U{9t?y3r8{6R{fXC;%2BIF$iwRXJJ)R=l7;zSBzbBTW?_$D!qV_jMOi?{5ND8G z4RzXXbFtP)z>NI3);E_@Dyi?E;NiOYMYa+Y-Qj5aR;5q*is{?`a|m*+7(fsL#9p(% z6SM&VYO4!(B4BO>$wwA09_*}DU;6DL?P5NhcGd3o?D}unD}7k#b(5(!-1w%kTgC({ zO?wv^<~@WmEc~9H?eJ0cQc4dx(#%h&C9nfG0pqGiz&Q?RV0zs8n8R>e?GCCk${ko7 zs@?m!tH|QLzJWbL*uvaivl!7oOrn(M{x0|K`zpWFowr@Yq7TkOCViYcc`PZk z&H|g!vAyB$H-HHnLcz`K#UwStB5WKc01YEKk-U~5<)a9rNol0;BE(w_cRnR0-7trk zH#EQDj+*^E4Go#gE^W(Z@xRFevg|nWUq@Ko=I0Y9kCJoaXJfuvQuigS)RimjT03JuuP&b(z6kP5 z-m}OxB2{Mge%}A^_~H_@9kkiqkwD-klmU|i41voX_-QZx3Empd5BTV9L2|-nwSCI@ zlF^#Mq+ZtCR6gO&!=KA0>s!N!GY-ohopsBxP0v~8W^uIlPj=#=o@>D3LrT28S zeK)AxixRSDLWHJM9dm4sHge=%w@|t9_J%Jfm-U7}OLpSkmDolV{6hxBwK$-7_PC>g z;7a1ZyiQ`7BUV?D3NLc!qx_D>i#?-uF4#J3p>?PB_b_3BpV+eGf8x(Oi{Vyg-wXTJ z4=*}pXLhl6@^Y5`Vc|?WqPu+XjPQ^30znPZ*b94xu?DjNFPKJj$sW0si%zR;NZ$sXfT{dki<;ZPD%;<^tT5J zTiqFFvj7F5&aL>WFDxd?10dY6ao(SXggb;70)HsB8g4Ug?>`^8Ujpf#|IU@EJ6qe- zzfg0tF$0pZ?jv&bI@KUy>#xyM2~wbh?uUeO60KN-2-CtxXW+Qdo)5 zMgFL*G^MRk+sQZ=C70b_%j}?SO|T9`Vq`*wS*(TFjc1F)AjNJLk+N~5l%Qg3Mu866 zMLVzX20R7*D1ULq2VvPZH@*rB=;aIClB20WW@q7QtdiWY43A&C7bs3CdgWcT#;J`J znk|r+MeJ)Mo`Mmu9AMC`y)CY}JYdrjlmdGX$sKNiK7ak|t#P68#i+5>-i0K0P8L5s z<1>q{InVPts=6;4+A6j!lyqVb*X+3rR@NTY=WQ}J%ffs2>X;%G7Tdy9T6RP9B5Miv zD#r*hJ@ok1`B<?+m?MGL)udS-&$M zY0mWwi=!7o_T|Ymgq}miJ_0|6hR|OKo(Pj#8&cF6v6y)ozu!@XL{~?!YIq)SHGG}J z%x*Oxcp$BVCi;n1+$`pnMHg>64dlH7H01S%uaeOUFeFA(ZOlhIJJAmWl3jwH<)}%9 zg(qyiD$X#;ij(}iBrivEbgW~{9q+Q9oUB2VfZO9IHZ?kH_P`mWU>rYE2pDw#mLTpN zQL=M^sQb{>Qo3vHR_@CBX{&P{NnKp7S7X1*R+&P>%qNks z<}02d6|%}hHyjW8YR-nF3fK|f*+RuSIdeAYh>OX{)(J3Ol~0LJ`!pQ4>3|8%{fA5< z@{Ev6fDl^V6C#X>KfeI9@!^>!_#^%5rRK5^)(`J?O(k2eB>jwwe!XM+u!-tQweKCd zZ_%#N^x`ZTMUb$xjbbsrrwLt*>3zwwaoh~uKP6l^CGCYAzv;8xyzj|l-fs`>nmoNR8p7nAfUn31ePdEQ<~(0a1#;FYflX-m(& z!y6WlB>ro1D3L%E0%pM()M7*l1C99HT$Vlz`_P2M&T8PyrrD;73U7V(Vss?!?Yh9f zCvgMZA_nHk@Vn&07VMn8k4Y3uzYRxVAWv96R2k=hxu5)rEgw*L8nJ3@3B27c%4wx1 zVN%j-S&}+>V@R%-)}z7p+5b(-<$n}<@<~BZXDgBs$qWLN=lD*YvmmPKZC&*Z>8(lC zlSM+Go>mmMwtArL`hSb_<*QHz(ml* zuH5!;-WC1+MrPTIeao^`&a<%X8$jhv6MV9pkLbT(cE(i+-2|wXp^wyOE8}FQefmcH zYMj`Hvyk(n)&~43rRUNaYiNI2pCJN>zckzMT;(lLVmdr5K9N$TG=X`&ajJ@))PKUZ zk@nmkR~jOef&Yll$C*T77AbyoPYlO0T9U&+-&$Xf@6((+UXk3BPX18dk|dHPcS$Ob z^udSv&5zd@shP{&1^ub0w@3(uPF#C=64wqBdvu58Z!i^`lz>hS@(3^ZHYUYy{00tI zpZ{CCA6GC3O2kQTMy3Qm1VB$l8BUJbIk#Xdvj}f1mZ1t?jt#VqkaOl2+Hleg65Krn z)C<%DMoXJ%15z3Ok7)$_@5qeONTt8hIpuVjMD2daxg*g(vBwoR+}(y|)CfSn^iN!@ zhgF6)L#4*@C-bHAWY_|SnNQFI8@9?qPw`K@*&|vt%{YU-=}hKCzDqcQq{ymd?(iEl zCV*Hjp8fD0{(87L!2aWW1E=m)&4|_$-;)`U;l}@G(H(1VqbzZEiNOm&N|St1+9Qk6 z2#3(;(9cJ)w8XTYwv2V3FFj9dKC2%)r}7=M9%jxy-%E*O>D98K5hN+O8g^^5r}(*3 z-=vSIW`H+;!XAY#AA;g#Y~-Fw4GX312cHWeg8f~HT4;^!w5YH0`qut|Yz=*NwYANs zwX*B8XErQe?GBCI$6x1+qg&5&6Z2S0x8L^g$ZJns;;8CpqQdCl9{&U}P~qYRTv~Md zeQ5*}i9sR976)toYpymA{uK)M4+k};&OI;(J>6fjb$$Md|@+!9J; zs_ewFjTr=@mGI=;@G34Y53G{OYb(iL=C+;$wm7oMo$Jz$M}0TytL(BUYSY%S4|`Qi zw?ZIWpIKwZHAN@kksg$FZfNjW9lbA#Lw;@4e!6ZSP50@vDf=n2;ma3k6XUb$*Pmbt zazSep!O~#?lyu)X{Le1JGaPE3b7lDfRjcLTIm9O!F}_Au)7;-ZrGIYL#3E&h-tH=P zbCA(+o|OF(m^g)+B_RcUth@J2`>C$)c8FdCxh{CscK89(UMW%mo@vZj%y?S93^uxT z_}wN6VZo^P@cL*}-%+vgcY;U?2g+A2+7VVp4D|9BeSD)9mepfb?B0|re*{A{2wmw)suG0s=vvB>>I9)v-a>6_PpI%zl>^lDhRRs8Ts{d#>i-hfMd{cfC_(%4@KPW97UjPt%7b>@6 zs05%7-$6d9xX<_;rT7e_kj{s`>!KSp!W*|U)_jEE-}*{;A`#(m44eRX+C_WaMl#WQ zo~_pLnfu)5Sngu?%H`WnM@6i=Tsm|M!Z}wosaIu(hrA2BA+^cKiS09o<49tCN>Fr? zbD{R1SNh*f4N?xaEfahhh%z9-(RX1JOi*)-<>;WkP$hf~}pm}{ebr)0cD9K+_vo#ICkv^GnYNwDfDEv0?c-rAJc-CD&Y zWN0@MRc(qbCu9X&vj6=#M(6SB0ii4ntP|)oQsTT*a^LR9 z_4PR88`|87!?3PQMZ#S7Y*+a<3_o0t9~ySb5klfeQ%pxB@gCl{BnFk&SU%Z#<e<3kdQpsKsaFgdFBQfwSN5^d_#CNx3~}2p16+ug{+f z$sM{;`CzScaHi;6)&5pJT6zB^w3Fx$aKZx`p4S)XSX6-aejZEow{WV!OOiHVYa6A6 z7Uo+QYPXFNeA%>BrNnge!>fm^z%LX%)4{vAyy-D~9))6_9T2YgfSCc(n9^<)iA%g; zqc@3HqJ7WeOyil9?s?CGO(k;{Mv%B{ zuM)uD=pH0RyW#=#^=QD;8z!`2>kEas76|43_*o8>Xm~P+X{SX3HxzuhYk#+dris*`MC9 zEqkhAbqzbd+~q6aN?p2BP+X6q=XZz|roB zFz8J?=FdU^d2pobr58y;t*jN=>zs0&-;Kzz-PMF?LKo1X>TZcg zna>7y-V3yt-$MJ5V_0(&ko1wS|ikbZBtld!A-y zsZ`o^zX?-9Jp*ef*_@OL3s*9wy>DV#n4)q+eB~ocE_PZYQYVBoD7J+wjy-qyZVX!U z7=m8Q=&Hfr0}?5E+f+P68+TcDb*vT=?^KR|_!Bguc%?}(8h&agVz)Q8OJlk8T%8rG zN~^$jmEo?T*@hGu={AD0h9Z}Rf)p_nMq4jM}I|1rjXo1X~r!Y9Z`Vt0X_OQ+j!`a@aZQsOUaW>$Iaaa(h5$8)T2 zQo=>Ktd!YAP_++ICHh3a`*Bdkoa%=qGAPjH!AWKAmA`nKWhYg@9TrZ>{~;@)vOlbC zs3t)hrs36!Ul=YnCiDP(qtsvtLebL?pEz=RpoG4uAeajNbeaclg}ad2@XV8e;hh)5 zC~516^gHbvbgv&fYZ>yG7r-tu+s)-5sMiPHRuBTUnd?Wk5R6!s^Bu zY#E?u`k_+AbRgrEzFt)pb~CokYX^Q&SN);PIa*FmQb!V)gz{sI(b)bZ(6?E_1=Su) zLK}&HUdt*$j8u9~%k;j%usPi;`YM_~Vd-WQ(Uek$k&yRiO*XG|dQdquP%##!5gY6$ z8QW8s&gg&WR6H~z(XgoABS}vgeg7eIkxYh|QI@~h48u_1~+oXru{<|dp<5B<; z{&q&wz7&25>$yhs2M$~bE)iDTURZ9R3Zbn-4=k!}f< zy2W)1>P1q$F_mKip|qSds~D${$|C&d=rF_azG?xCqPGTbRb8;EknL^ot;Uqk3;)0 z9o(HUhCH@{jN(~xLhlB-2P$DBrdWMLLx)l!Dl$-tM(X033CQ-DKvE9j#wIxDn|V(l zI31a_>YcnoGzXxR;J6xNT*w0<@rDJlCJ{H2j_ISC?{6>r`;1{%q-o8#Wj~KwX-cM0 zaAnfx>Yu;ybV&Z8u>axagY1AVe?%p|B2q2+78CPMA+$M;FBWBagHs_vkF`t{ad0?6 z{Qx|`#0X>Ag>$Z56=qj1Xu`9Aa zaC&#KCB?y1M@0}+tD;?JO>>gFTq72tZ^_eYmF;cCFei57LQ&#^Cl;moA^d)u5v7jD zE4`%ei64{SWVMfSekV1m>^qvrcE=U427YUaR3M|5s>;$gnlXI|HWC%^XF<%NVESG= z2=riSL=B*IsLW?yGVdGD5<1IQ)>gU|^rYw0b-9}P1;_deSHD%rZ_Z(2HP0!4lw#5= zwLfHL9p#pDIrnlGV;z}_?c4tZpZaHy>2K9T{E6VSJbXU>IX+Xb>m6aB%<6N8=<|m+ z)pcjDr(za^NX4xZlTxrDay zHz(BK%(hYw2A@PCfRB(KW(18j?`zpO3beZjXRNpV$>|Scl@0!Xvh7b?9O1Gr^ zs`$a@7Av?hQ!%^A9+1R$$I-L+?LJF8C`d-;hk%=)NmRE{%ZT4INIS3D_k<9JvG6p` z*X$0n1xFPxtfZ-g->dU{tE;|U8uq1DWNth6NvfvBla%EbvuK6DJ`NSPG>lQ3wCil& zHGj6r>vDX{3dEPSBu5Yo663Lrx!egKL2};?!LDZeUtRS;KB@g>b@xu*^_lD#((=3v zPqvqi_7;NcD8%m3P+OGtYB;O_d6X|N<#q}ujfkI(!V)=xLW!BPgz~LPAt;^Bz00GD zY%d>GTw;dWw?LjimjwYT#9IAK{dH{xXV;K&tHiP7u+8MVnq)%sjE-=M3l|MC@Bhwf z|Dz?Ce}ympkBh_o1Q7$pu()ydyK|A%z+E1SH@E@=+K8TSZW{A zS6s5%%QeKfA2#-ZXb=&I@+^am;@*3(0@3)DcX*cPs!@;e_wecHlJT`0P%j+Ss2pz; z-B`=>u=PxMy|-j0+dz45wf$?G(YmWKv?K!0xFWAF!82JKh6mLWq^-WuQv%>Me*s=; z2f?H8uhH-k4pfO`v=jd2?VZ!B9G}7iBx_Gj8jI=Y{Q{N>r>UF4zx>jf_GIjw^oOLY zjl){XC?Fo%3&g`qq|2i319o68VOd=av%lS7^VXN!RjS-w*tkxFOS?Axw3^l6ZHfuw z*HS;8RJC5NYTr5M#9F^or*FlL-;an1puHbR?hT0uUtXx^-AM$M*qb7q{m4DN#o|+Iyo=!HddO{V`4A$~0Np0(uGf;d3m&6$aY-Uf~9h1K=vD zm17em@wurm(ik8_W?M22+;ECR*&pG!ThjE{5u9_tM8-(DGD@K}=UUn=9=2PQhX~_? zxXUdR;EqFi*+ZeE$@p~aO<^BZ&=Lg=QdVMM^mleqXJal8>I+nNsx4VGR{BBb&U2QZZllG}+W?{= z0FT!266z_Ujw8eFF5G#Ib;~XGdhEp*taB#RY-ytT7*+AMOiRf0O`U-u*ZS>%xIuqv zM4^-Db>(iGuiDQ(0Ps?by*7iAk|d`Z=b|GYlh{*p%h7-3z!qR}s)Qk2C`uBrt- z2=Cxj0c{;ilzAJ0x~C9kU8*+Cc=vgX0_R2hs}jnZT(Mzy3U4&I-H-&AodexWm(aqZYCoEG9#9}m9w8YhN;0ewyu zbHWN|)|)4^+LQ5BYb03pd$XG~eHjX5b2QhfjyD{{3Z1pH->(Jf_^ZA-lUzsQcv#c% zhBV+`lq@}AoOtu?Nkw0b{wV~kxWmk|h6wuVwNMxy?tR?PU_l*z{?_HdoJHBKVO#&F z_LoTC9QZFB9vngs{QZ8^^p}W+cE2mloWIU9N;;~dr5;<7aINzqPMffKf;K9QT&RN1 z*uHC~nh8hO)xq;QXO736^k)0SZm>`g z3j`&^#xm;fF%QWMWeA1jxkVeN6)(yKjgIycr$O<9a06;@x z%J1^W!uJux_OPg6+=c!V>$KC6!ezcXk+Hf19eM0?f6zHYTVqrzW0|OUG8fGXYtVJ2 zGi9z~Ol!*+v>Yz|y8jf-#Tl^`!rLB|Rqz>-L)61juxqu@Zjd`)>$_mEERZ!<@rsi1 zF*6C7S%A#?&QGB=$@f88&fhNy>WmD!Dw|E%(5WXRb!=?+1?l@F(s0u;&Z%7WS2c##0x!1zIPe#2am++Zk?w zS(!?pL^_+akWb`GGuOEVRj=+3gR||l2~B4*V%gH4-&R92+$(WZxy?nU#tXqo-&*0* z4}6*p>@ZmD-N%9rTw^BUMi=a~TKtP?&Z(X^0A1WJObJYXDxZ>1lQOG%&5u%4WCY#L z8}Em#kaLT@vmu%7uansXABA6cS5cn_3pW*!>=tV;48D@_ru%GR5{|6gZfl=K!nns3 zPp4OIuU$@6t}0Xo85dAUIWW44o~Mc7co##H&=a9?F4V2Mg#dMdD@+2rPel?|*>a3} zx>z%k@1bZG7hmp?&zns)7c|a3&BCU*lnJi9&_TXo=wnszr0SZZ?p`3DtcPo1qyBQ4 zF5lRmZKQnZ6PnlyTG!9*v5@u&{hlH9SBB8Pe>CUXrs9O^O}5B>WA~bJoTD9d>6qRp z8S#ZW`ITKO9>uO~wzXuL6t1UR7ntYS=^GCVs{I79Q5iilzfV0X=tw-oP>DzO0Tpdq zBGDH0HuV$xTsAL{k3+TSoR!$ zgxKdIjz#rC9B}F3kj$4)WWsfOIVQv0uLu8Q^P^w7j1uI6#Dm>n0i*i zF`!2HfcCuc$M|4?(7Gb&cR@6rego0`_X7UP zwU!`Z0H=}y7@%*d#*!w-jCgh|I@SmqlbCCZC1AYlTZ+oj(?^G?LY7QC{wc{Be3o41eKk(cy-QBP;Q~=qQVc z=+ODEgl=>YBSdY#lSE>r)SoTV*{brdeXg+JQ@`tFm6 zflfF&L&6SWa_VJ}FMbHZYb!-GjJ8^PK-_j^VY4tvrq|{2j7qyLe>R#EYq;RYUbnn6 z=JDKtBoJ)OMuu~Qt?1QH%l3$sx69f6)mHxRc(n80<`_i^;ronRaF^tYEpabP7~}PE z`v?rZb(e%tz>%FD6`XKd!pg)6SjQrbTZUx|KzBxN$3 zJRHKs@4$B$_O7VN+JaXp`2ka(3x+E_b&CGTKK|S*Uo0=E^JXAwvAMXt)KenyzKqSK zjEz-irGQjRln_<=SgxTI1Dyj3Aiv?{p(Vem=9S_4FZ1+5PEPh)2ySI%lC7@1)>~wJ zY=TyP^VUewO2RJy>F`JHb1tMY!d(hKK{7HxL2i2kA>-Y%g<7WMK%%FYnx*n#7c_6#$IsY&`7Cn@p4_&jUkUiycLU&k(OA3IJWA95_@MrS`L@5>Q~$WM7tGj+N#oa@Gsl;8 ze7}gTXRMwMZph>?JpSA@n7 z=a+5#nsdXYb|guu-?&3>6_m&Jf+dF4?DlAv8oYL}!MawkU7=4|>H+KWVDG)i*!aV9 zqr|65Z)hUww?YXRF*Mn>Z5k9B%!}o~I1bO}m!L~>e}di}lXfRGj{ACIWA!T3l5g|v zr@^AG8ko`2wiGUUY%K574X3>QPE2*GqN?$0+xxSVjn&@vC14>%L7mrc8Pg>lR5!dkFVDRbGg_Fe=&`ky6+VpRXdSk?NirM> zG>gdZ;2VDJ1H(k|;q-`sw7YZCH+h{xx8V4pD3y4HFa^cg}8|x4v-#uAkGHAHnZG2l6@b+cTR7JTY^H5w5J@ zX^vap0jCGQ6iRz?H7K24=e?plMQX*Jv$Stk?fL1hw?J^w_aVbcj$4_Gj)q++yJ=BO5O?MPt{6 zP#u+?PVek7h;aiR&XXVGGjD5%A)nKsdqFPw3&ZpcGRUl2+Y4N07f>qCIAwHl4hzjw zSjCGPxeNw<1vaomnuE{#a%df9^|V!|{s?4Dq~Z^B^xYF4GtIl2tZz>qHGJ=};m88xijiqakWsPmuYAM+ zvXPeSXQsoep~(Z)!a(VyLwkE0CE9eIVlhji{>vM(zK01uhvLqs&mAK++kl8t1kip( zmcb932#WT_^Q?+Z0QE>>V;rJ3i}0hOK-6X4*PhGaCFV9Zdh#P*DvoOwa^$v#u!ms% z4Wp2cXQlCH8T~-AuogBUu0{whFp`Jf7q6wNw({8J;i|etSt`VA5gsG4aY<1i6*$&L z9P=|kcPEf?V&Zj_HULl9x!t|v5+#W;v`_XLU^J>$yCuEk8F5_Nf7QJreCSLWW?c%K z@Fj-g(ZqT@AD|r|+vA=rO?9bA%$liYiyg!zk$(Dv-r|ea&xT#qb4czh%AjL?svFJ( ze!r5VVHnlLXLs@q-I zlYLZq`RV0r+L9eW7Yp0BvzAlN`j!>WZE>hNc>Ye@_HXahf8?)fyYq{uiL?iEXzz@rY4iS*#CN^B+@?=*`UH(VW>DqPXOw<@FV7HiGe&rXrDIM5|m_I zz@D&vBl{ zgxgpge)$-~ftr-_faGG0yVW(Hq(x13mS{~@pbILoKXTPO$^>H`tI=eZd7h`1%)ZH}^nW=C&BJk z@VU*KFK8Pzb~SIYpil2_lYW0g=E%Q7bKMb24P}2^Y8>Mle~H`Y%9B@)8u8-V63cxs zv?YG&C&*Cs0)=v_)3)zf0#H?OdJ797N&$5l{~~Jv+YX+q#KsfU zk^lZ9!G#0FXH>;T-h{4^#S{<3OAH1ea2@o8^oryJ3l#czrmB)47F&dI)`mr;ZA;c zG_a{mw;@a(!t6CXwJ;o}3xSY1-fO(Jjx$5OT16Q^#Q4dghVzY-3P zO{Ba-mb)Jj?X`UJ7k=+w*Z}{cs3FY24IT!(w18q;`6=M_8M809bCTq{4VMu69*Er) zOm#Br(LRsXeq44Nx5saF&1jLaX3H0U1T>h|mgK>*@{wEd`N6WCI0Tv{%IQ|lI%+%= zy)<$O9>SBmXgJ6VZiN4`QU6{Uphy0_5&TuA>!1FJU4cyGH^a9fKxGnoS;B_x^0? zD6lHy^%c+V&szsA`U^#{t-Q&cd0aP|&L47tA8N{YT6&4n^d;T2d6+g;6lz*1Z>iwM zC8peSyR1XTuW~j^IH}qmj$X^2v$B+Yb-|MPA(a{>t-wo3TF@i=)(4sY)v2jZfo&_p zwz+`%!$No96^silIQlWr3Y>EUK>;6pO(%xwv=*d;#CzW3*%)SE!LMl#A$OXXo{0q~Iz|E)3l zhnF$h2{r-Xa9oVG2lkf}6g3)N1}pr=u8Z}}X!;-$1QygQGYF4v59U)sjqupC-SW7` zsVe`aN-6V64^T=~2&ny%uxQ6<>(8)s2rjF~hOj@g(S*}RNOworVD&z|Hs932U5K?{ zPz*wx$0fSx#*<0B(@7wNR0y6e{n@ws!=wGr?#jRNqJRIf9)#l{HiNg;h@SOh$R97E zbk`z?f&>^&tQ7AC9IigVH{`-JeEI+Yb-CRkEKhZ9Y^PB}vxCn(7qol0Bd^!7(ba|;bNnyvh*xyEV6V7fbMd3WGp~t?Vw&LdU zF;!ntAFMNysB=lld0`Pk1348D|PM`$ppR)5ss{O%KzG$K{$b3WdNI?C*B2q zv0Q_i@8gWDakl0}{f8JfDxE1AauE@ly${ULRRs}O5w3(OU9_Pfzv7%l9})*&!+l=E z58X2|G8$uS-dEXS_XGgini+|Bo0EEt!l+E_P|9_$wznFbw2eik0B>@=6xEUU> z(t;;B9qVBOmIFf>k$Iu$uSTPCcE(dak=1qGv-y)bJg-`#RKD(GB9dC#n%&1tm@w&O zX^q7`1Nmi{a2%|(ukVcgmyhdvAD{I>41U={B_}f3VKLzath_(Y0N9%4G!+*@Gob@l z{0t2!Wp-8Uc7Y6p-{81JU^jds+YRPlK0YdUeBY%lado9#BV|;w;zi}FzVi;5{i!qi ztf$A@vjh|+&H8u9Tf*8p+O|DlX?fg_=f8f!>p_5e@c;@lgMr4!MPvcTsW_qU36L}e zatXhGuK#v`pwK95|@_SVwcMJsyg@8x91K`Y^Ad4XgyXZ$2H~}oc z9F??fKyo+jQ)8m$UVAm(dUuRFa(C2e+DC!CpZ~1Z?9>TQh5rgfwuX^6H1XN^VEQ^D zT}My*t5@A~wfO^kcJE${bMuc4lv?nrK*nm79P3^G-syM)-e!hj??K@J=21Onh?oo( z{|6=)kVc0*&iPd)&I~F?{1g&av-bC0aev=_`Pbd_o69>7xV)=Moquw9vy=k{IJ1L- z?A3+N-y*9TfDCPKuMyVW3L=3{e}!UT&|L*CTpx(`pUqFeISh?)LCo}(Tpix*x3+D30+uUbV-(XPYrsFd&m6LJhzN8K$x6lT;OVL22z0a z#Fei{a8ly$y5d6w4}gZt5(2^w&?MtEzs5dGsmA30{^cAsl8%ar<9r)B}d8WWL=}K4zO%IlA6>uv*IU=_?VAxY4P|d$?RQ40}!O$7T17J|h zx)F0A)unhnJz@>jQQvVVF;0l+4@5G=>e2hetEWb1S(^kz%}G77;tG1WJ*4VXE{PW)%!ARS3SaBw6(3MK|SsGNpI-IWj1gT#GEWjVYsa(JUOa4m~A92*5s5kc$R5f`f zj076;1w3GL4#eE(R@l1%*n|q;uN)JATdB81_a~^a5SDQa+m-qW(i59Sj#@*GEnyWL zb!-3o2KfP;4Ff1JgdxQI3=L<-RU=}G8UPzy?D2O!20;t+vE>eLiMabm&Wl^q%aI;hyP66T{Rvf zz&7&0^;9PctimOmcZg*~g6|)$9QbDn`=4c$4ap$S+{I8FgoU1P;1+Am3Iua}uQ2-D zcQ&DYneY27xEhRPd5=3c{zpuRf2y$mDaO>{IDj;6eHjY`u4ML$k$ZJ$*2y8FK<4QI z0BfAyJ3^G9+BMoA{KHMH|6FnZbL^t7KpVidc}M_kyYYza`X4n=ZK*@R%ycGpftR=Z z8eu8wrCn=#4!%s~W(DDbwK@iNZa1stVVV(#=wNu_q% z)AfcRDtD`jCaDxa!k78%^-?y59`&>I)+hKy@aNh5kDNZcbAUwwq$D#wkHPTGFj?@C13v!Oh|_=cAO5yG z`kS~SAfpN_^{-;{0dmF@_16P{8T*&*2!C75-~Csh+TipZBnOPIk30r~5x)GGXz-za z$wK^(!c=;r!z!2wELyGsLz4gJuV=>qI7RBfhyg1~feaY&+Bo<`w|(5#3zk&!S^aGJ zUWwyR5Zr;-6@Bo%exk=4$FZ%AZruVCHkQ{A%-d+*I((@EdPUCww_WJdWa^|+fM%F! zw!xJ~$Ic$>x*)?g%;PT2ubsGTxkB_`2Ia$7L&h45x+vn6pGTLPiYIFV0n7&qm)OaV z5LfL2^?vk>(6D@O>!K0+NXDzUkv$tv~d6@#u&Rhj`smR z5HIi?>i!-YI@*CLM|Y;^S>j0LEKKcIcNJv@iarmK(v%si^3l**tuV#91Y7GQ=VG_B zGdBv2=~WYAZzv4IH?q)amu0ya!&Rj+8|RE3hWTq}H56vZv?~V;F+Q5Uu4QuFSdw!D zbgmaH2@@xrZTXH;;V1S-JB^g^53&1LF7=sXF%)D>;g|`Y>wR5G zcDsp>a#-C*N_WCYa(OxL#4HD?K5|yTs0Y1hZHX+yd!n62(bJ9I5qS(3HfMdMJ zaVpl^i9V-+1u~VNQa=YJQ>mZ(9zF}PD7jX_=cXF%WHI?8K`##zFbLjpj{+MpylhJp z?X%*-M{*qOal}8)f$Y?lSj_e6`^GzS6n4!4pez81YP3DkyfPCk8~GVX%}b#7Mb(|2 z0~D@}Gbkxk_2)YV0Vj(+HGvpkv0V!uhZN2@nPQ#KyCafKak3Vqss0G%x5%r#GR849 zv3!EDUULG@yYf!tZ=BX8NBqYwa*$Dwm%@`*M&0I={aHDE*x8+`*7n{{@(Vmt9j)<-3ZGz8lS69LE_frFw;d<+y}<9*GrCp&QM&tS7N zJ`a)l`cJ3n;l(A@D7Z|Wz;N)Gw_OR2aZI$8Z0pt;rFoJm{{8{VqVKv__Eak(8t`E! zRQmAoc+IUf)RM2P9vUteZKL;W7luIQ$$s-vUUY4K`a-1p;5GEFqRxvEZr(f0axUmK zsbeS_VJ+i#G;C;6+9pwyxS8#j$)u&hZgVi&E&cf@*C}2XfG2!ze`DE4+CgHXoT*OyqA4`UjT`CK$U6wv(y3 zW!q3tjg)Vj=lx6lmDPsR^_n2~L5SGM7Eoy;LbS)H{+Lt&zIb7rE&}H}k=CDYvwTU| z!tmi0*+nV-rq7TDr!j*UR_<;G^hgPe+NuqxDFYXz{0zPUpR@%R!js@waQjAc zLB2emtG07THr;fi2IVWebkOi`t7x#Ha>w|WP?ZhrhZZi@ooGM2u9w!IJKI_4P;Hn$%X-ImF%5F!}u=-z& zyl0AY!Uo#mDvJP5PFgu}+Xl=Hs3A)>>jk5ZdFjxFrh*kIn^sF-5uaKIZ543IwTe)R$hp)fAu6^rcxBofq+ROjIl=@Lx39dwdaX|rslEN zI0Snu(~hlXmj5u3+8O5g@F3=(67lQO(n=_$%g;JV+~`Bb$@2=uscIw)s*MM9rS}KG zpueu|MaflT31u7q(+%GzN{<9IW)_vREAg9#)2?tF*|?%nK`{Phu`%q~C+w#X2~{(C zdB>)bJ99kmt6kmN1FTZy>#pkO9`u9m-z&h}FJ8Y(o&wVvX*8x0k`39};tyPl`f{{w z)|?lu`LF5LFih)DP~8PQ5WmbnnS`8}V^iHWe}b-#oQ1*Khu58df|%ov`A#+?*zFbm zh^HM!M%XkW>eWjC7Tz4;{ZG(TJcjk}Pw@caHbRMw0C2StkW%CYNJ%Is|9%7Szhs%& z{gZ9gf3mp$&8F|&_%Wg<7MT&G1fW1nj^#tLBAd%&6-#o1Ylek|z55%5jq_gmu*=V6 zc2sTk)~fCXNESMotG-qrJCTg#kuoOzVz|;55KR*B1^_}o!_#el^`R1h(&1``ql0m5 z)4C!rA3Oyb?q}iBwqLX_Fh`3vjr+VR08aP7tuuhEE3Vy8;yUd) z-uS%d?x9~Uotz(yoWegsQ}OKf+@4ZK)euu=0d*ns=qX-tY4?OKD)0{dj2$DikEIsU z-kRQi+bpC~Fpa{Wh~ppNs2Vh>|MZ4LYULG|k6U@;$fv;oy&c+Q-&0c=nzeTJ^|`$N z$RYYChXVc=`|dqJWVIv)_E~`F09!I0E%~155f+3zECovEo)yB%0{~BO7x~G?7)Ud? zp43l(N9%c`{qdKrvA#u3oe`e}o@Z?9%$AukC>oZs8n&EfKYn}R>q~D`PU_toh^S9G z@@&stC?ruNeHoxpNfyRYm1o)=8^QrxPOme|bLrM|H)6Xb;kx~}L^j__|L1a`9v(sq zaF@prCKq4=;O({WEuw=^74bg4lpur83wpP-+|%G&xue+81?Qdus4OQPSiekN^PGeF zbF*O_n7)WV7xMp zs$1PT1JpLA;RVr;=n!p3^nguh;vW(HeaFPTGJ%9~X0a(;54%#FjuD}uofDDKy9XIt zl&xeh4fgjBGXB`ok&>AJe`juy-rQk{QsK}*M(eh5d~Ba!jCE+LWYRjXrJ63F6XUc) z=~H3+Hj9aB`Jg|Men{^i0}JGj zHkl~pRejrN3d;p(oHY!^W3K9MWTp5Gys(II=r_8GCQ;CNvXs!vd7b)PR;i?K0(p$! zBrO+CY#hMS(dZ$h5t6ZM82V>*_$3_T-rScx0A*MCty9@Z)lR-jwu@{jRGB`9-dr(o z<;AI=4We1%VU(^DBGEjV3SPw+Um-puoXNGDmRw5S?{9fAaD-jJ_&g1QLL*rx$7uOu zF{CQ5mzpe1>f)AXA`Nv`?0u{2{&z|z{?w~8xi-2lZWDbMfKLcC#Z5HhN6-+-dqfjx zpWU=H$Mm9HzH);X{nHlHmqnHD-!Fggq{b!(ygqjHGpbr&m>EP>W%*;CQoI^e7y_?4 zCT~)-m5J>xGv4Oqup--`^%;7?8dffFmk)f=!Yf-7*1NM3OiBgQmKUeeEQ@VFKC!Y|@k%oVY+cI%cYIbi7Wi)4 zB6D8S2!`>YdgmD4x;>N&0JHtTqe|ZsU83Eh&4J3U96S3qtZ%jhp^MOn#3hHeelwrC zi6%BgM>f>kygKdg;%aWmSecg=;gZO{dDDk!G~B;fX;dpxB29&nI;&xDxEhseESaAC zhDIW$dN3fz=Z?fSV?x`YxTLK7R)Ch&voTdI-pBoUI(bpb68c?-z*oP7N4o&V?V~N& z_!Qb{OKd_9$h!jw+w)yDH9HH;whUC@yl2xs)Qh{Xbc4OTtJE#j4o|0s_+6CW+#fHz zHNPXF?vBa2MVjcxnp-Z)#8@;ToE<62YJ1gycC$Y@Jjxa*t6>}-v^UOjl0O(DX+|+E z)AaH=rBO`cd@Tqog!o26J7IhdDR=Cv2)zxy>0u5j3g^LOKeOJE4QFrRFwEFAI(=Eh z_O-h^hTjlWy-y|W5(>2=;mRA- z9&le$O}t2JEX+Y{O$)S~n8oeloPY4`<3-KFWgz`KGzMU+<#1#Z&F0OAh9NmUI=)iT zo`TI>t7%m|LZZYzhT71z$O6wz10B} zp?O2b;b)A|4*y8-4iLu&`z-vMP|ORg@7cRAhZe|>!N15jZefo+1+syD4dW^0sO)$06omwf6XH|)DYGG6o>;d$m%Gx`$ zaB99d?WmdpVXN(jYGH3SSrgH8TIGF&V8Nq9jZgr;k?^Z?xyuR0JyGO9x6K?G@c@cQ z5n6mj&0CS^aTYpV*QEDVRQ~G+PQ+Yc_ox&T)4A`tts>>87-_+JRQqtexwm9~>bH*>J%!Cf#v5f;P`}zA! z+Ov+rsqzpiitm(50B?bY!uMtl1Zu;HRrTDCO2JVo|8T09etEx2(MR{B&J?@_fLn*7 z!b(|9DUah7sz3Eab#`LGIfP6+9KEIpS^1Q{+laTGs|z{{STlLuIM05m|NfL7iH)L8 zxy_sw{G@>OG|zdm*p};&sCw4rRVMOem+5k*UWtYsPX7(EIsP`rro%Yl>m}y=x%Y2M z#+DCqS$z7Kjv$-6gSZfoDGm^OmSA9*D{yoxMra9YG4d-%TvqtXw|caQ;1xjWTVTJA zHy<~(Fj(LF`oq%WL|OFfGM%K={H61fL*in)~sM6GS${8n7BE(NB*4=v1uR%Z=Np-b~!-i@P>b+tdGRQ^tDjK>Q zr-Pf?AAV8aRraMY07$<&n(3K+ge@aUv?Q|1NoFZxC;Za3RP!VUZ(ZefbadCv@so5t zd{E6eD9J_@N9u4roQ^~P?Zxkow@9W7fa+HZ0BALcXz0#v-py`}Jt^kIh2}&K)LOrd zf(DlL`9AlWU(9-SD{S6)QtHf_QgGax5vo}08Pdv_deaplF2`!crQoeGOO7CaO)xq7 za0)H(92v;et?Jd(<5f_*xin0z`|O>s>eN!SuRUP~>xO_yfJM4awji>jEkrAv-D6mV zSLprGhnFJ~*x3E{52_Q`9pGw0`NV0Ck2qypUakZ^d}I7eN#I&l<#<%^eAs{c0nNs0 z8?2CW5WGzSVHhpJ#jxMS33FtuVVjZSVy0HWH14)PvYL;4lgRD(`Sy&r({z)pW==9! zgphNQ=LP**ccFrDV~JRMM<-5~9Di^hLgA2)y?Ol+tF2sX{OkwCF8SDiEgHnt8S9L?8hn81jD0*?Yd3clJAb+CFE_nKM855z0zf>v`_yE>|&hmv*7^ zHy(H0w#_+}MyLMyZbwt}5wpJPrNIH#QxR-ZMx5*cJ^gL3;&(qror`*t`xbkSTY)Cy zh4G}Dn3@~60YWA83HYsJT3TB3<>qNw*)da-PihIKpWeo>-|J-y(_Fa?@P=}S{{F<_p9q@%AMXzSyW99@pq&5iHvVrMw5Jdk2RJ>a!Alr%C8*$V8zij>F6wl& z5CLYxMtQw5w=j1xX0t@smo!(Dba-4@ccK(~8}1R_sE}PYX&0_wH^6vPLP=9?PA$R& zO&sA2X5~*(kmx@_dF6$8dCy)7JnQ-K8K8~?MwIDFKe3K9mH>o=?Q41zfQ7xEe-!Ww z#gueFU@flum>U4N#{cFo2kQtPy50#|CcWqb$6IJW<7Y+T#;-dk_lEg95S3A74HG3z;oqKE z@A_@hroX<%*>`*QH}6|i%bFgsU!2ss2%v#)Z7d$n*eyFlCUN9E$i7anvN2(aoB%vJ z4Ol49lY0(8k#m1Skwe7*OiP@fia_$QE_@xBojjQ7o`S1@*6EKQ`2YKY|M)#jCq)sT z{WOBpBrN8UwlG`4Yn)b7dmMt=AA;Nci_W^p1zJu{=!s4@Rr)L)iC!`^RGDDZ?PhPw zQ8|N(XJqEml4Lwmi_k<7(FnctURKFF0);nD2tf3sHih9bf2gAWUpdr&qc`#Am{9*E zr~MV0>%aNwzfLFSzpM&20wO24fe6RM*^R)wruFiN4XnZ2G^3#zyDi$gpq0x zvHQ#A+8h677X8U{5}w%;@agqFi*0#*TM1~-=C4mp z=_(uhW07a0Fc^ae)wIieytbpd)#o*%Xp%(m956lqfrj6>{-3Og-+uWo1|t3SjMzv5 zyR8Vl->=Az${=BCKS6zNH*>QceZTQ+l`A!zf4(I3FpuG-qg{Q4f|11sKov5JPJyuU zjuRY8i95ut?zV!_#1>*k<%vM%d&3vnj>iX-X>dK|+hWGd?DDSq)tC=!C>fD0jSTYP-n zWn?Y&I570X{6^lBX)%E|!lm9-3Yu^6uPrQldG3F?-v3-Nk>$4Z!1>X4-RiPIqf<{w z7G#SyNsiRAr3&={9B;?K_A-|KP4wD}IJi7qc;cARymr)@`*Yk^_u}V^BWA%@%OO6V z3#m1gm6s5#PXYed@~6+PVU82{<5l=4#F%&-Nb-G?qLpzPXzz6}RBy$AAa0D;z(SJY z5~AW_;Hv6Zn2}U*z~PN?SwU1rS@z52`=^e>22oya{0~Tyh102*u3(Kg)THROFhkzF z3knfZdX=agCMtBsszxHU*RCV0Pr{#X5&ik&^k0{w8;V5MjaS#~iyC~Vlhb`2h3lFW zD>iu;E`$vNxA>QLCVWA1z){m$;P zi*^D7e$AIgGF@L?ny#FrrBb(T;e&Tlf5p;c%d%amJaC}0FAC_dobK&}R+%f#D|STu z5qy{(w^I(F3*`ZQU~)|1=5;7~*sNq5tAUmFO0`ykzL-edQYdHCC^7A;ax3fUL(!KF2_vojs>#pmf^cdcMel`Q%$&lkl(#rUwrv_^J;A9UG9&*aRP9(l|Rv1m~o(A!g7-|Q*23GwRp zc~u13)J}hE(UFv`H}DxLGjHaC%u_sq*+2Hf^AATP^MuY4weM!$ENB`3lr!HSmT_j= z%y^rv_q(Ttx;Li?F7g0Qap-$6NT!Jo!SI+xdF5mAAqN_@UB(zaUkVC}i&PJ(T}S+M z{wN<=fjuPUOe~sp0ciAv7GI(%ZvN)6o1Vouua>KfDK+HqtFr-v8`R37USAMYr|7_` z!y+lw7r+-7|5Mcv24Etn#GVUi2=Km>8j3d{H$t@+8{4DL&k(W=@ee*YL-LMJs@y$4 zKv#=(Ps3Xf)we!R81C2DpKufXl$Rq;5nmYPCEQPEQRkN9`3r^SQ_$`rp_w3RXDOnR zdp7`HEcfh?5CLc%YIc&(EVYJT$#w?BQI{@j3dX%CDvGYUcJ?`q%t;4N*{{z|ni#%M z|C?6jzgU@4D@16)(WjE~D{o`WH9Y`8KA`cRhQc49>s~FCt=HW)t*Kn6O98Q{G)*RI z+}U;D$&AT1rgaRpC?Sot9v;w3-F!dkQV?x%0t3OKe0J9va6D8e;aud0Fekw26jdXh zPO9~6vK|BpTMl39NNjs8v1v9)X83G=BULc=UQcD@ zRo%A^PqsqJs{<~9?Oy(Bv(=X4^j9Hiu7L2QT z^`@p)(r|rv5fbz9Wyo#jumPe@4U`e;tJj}@{U(ORG|#+t@YwWGD?W8XA@TFZj{4J| zi?O46v_#*yCHcB;l1awzfh(RWaeD#xaCx4-cSE=Fv6|SQSNw&- z8vmum)M{N4A5j= ztoNZxIQhy8Q3+P{vbWadqU2qmJQ@E)BM?1)1KeMS6^S`8;ra27gDL0Fw6lM<2L5%R zz?RXkJ-{$~s2qM{d}L+V>^)#VUjNkk=7+77r0x5Y->z12y?)(dDkf%Mb++1R@|D?( z;3C;V7L9VkszUNNb~K`V%I+;?<{X}V08il#qZjriEsWD^AeE ziQW=026eSso6X!YqAiQHYWx8YqH@ca%GVz~@cM zyb1I=c#i~90r6?+Krs<=vw2L^-N7ZB$cy10p6@=cifOMf#l1;wAGp?#hm+j-63%e% z($P~~=3(m_>5n@a5iAAY^Ch9lSW`c<-wCb{b*vMoh;l@?3cyr11DS1g7k|DE>e`Z) zWt_3UrF5q??Ne@%Y0{O}Wxrc%gDhtsFnnB9Th^k8VJCHdjpgIvyIJ&*Gux0H}OShFecpq<wRNHK z_Ic#n(Ngm2E{a&MgxDC}10WOCoPZ_yFjA2CePdg_A#L*pAwDCov}u(N##FZH=iIW* zIX1A*1CC%VaOQqYl4Nf`UCF9PGpm}TI}V~B7lF1aK6MB8^q3^zm>MIx+lNdDf$sLL zzYlhY4P@^;9c#Rc0l*z2VcJ6S2SKJC}Xd;8}wSCAltsA{7CyF4m|9kZm?7D17>0bMC7kX(&*7&91h@H?drM! zTDm|u{@)jn!Py}{6fY_t%G+{~De0vrU=be2 zY7C;`%CzSh^15#^qD8YI$P$H>tn*(|z33Hb7k1%McOQ>~yOORt5A8-}^N+ ziH&jTiGu3`)k2GsUrgPPN|6{sSQN!S)Zpt;!!e1m9I3_L^~-bWp1u)Vw;OnKrAD4L zkjF9BE0WRX3}(Vs2KX#GcM5wgBy*e1YpMPtUVD(NS}r<)?gSmn16AbD6c;r)bFn z5}Z|+X+ARYokw}PxYv3NW^?>D$@E{P15^yNC&;A-=NDNKV}{M<)6<`bDyS}O%!aOe zoP3xiB({3CPFjC5H%wPmKyw9gF_OZ+2{TNqFPTYkzGP_}iX$iyG!8(iv#NjtpQ4vK zX^dbQ6Z0d58>I}onLUvdv2;!5ptODR=GFc8yA6)yHBS_A{0dMhf+nsWFk7$S03g1% zJTHkzH@a_g^vHTjqu(v<`PZNwSL%l6RzZQk8Aa2UN{F;+Y6KSNY)7USgiFJ@Gpq5j(PS&YvjMAtm>`@l|4Kj=nk<5asJHqnJF6_JG}7dE zUF75FnHai4Xnoq#xkoFuzlqMq8f1*`#K`3s8|Yy+BBanSzirbi;r+3qi+~GbEeQjl z|7ue^>KFm1Vfzg~P8U)tz7fHGu1fdlX>-oeaL)y{&tg@91J|PDM|-vJL}D{-P}!%G z^-4ZE~SjuRjy^mXbehs#|SRVDgOX zm>saSt03DyUd#m%5DThxq%D9@%vnH8b$+?vj35>feW68beu1hVAEzgn%{RZ`PmOCX z@ZitP&pGi8znR4yZ>76z*rvkn8?du20_BtN(%xju)!@|A(bz1I-&JOkjW4b~a~ckmn1gW-H9*cY4b*mD^Z?**d1tb}q= zgkFoj&e#R2xpjiaLM_=SO-0sqB2$KSgP%*t%Tw1!U}P-ijqZp}O#Md6I&gi6^{LY#&iwU3$jE8~*UtVF}fFmMAI&I7t!u2qR&@5SKA1 zU{y|EX~gBuxXdgBIPo4`OOgA12aJZ$f*DQzh2r|F>H>mFl9>BmCamt|W^?_3W5s&Q zrIUI#aM!Up^Uenk`j#7u9=N4AOmtu0KW~BHQATBW?X%qt43Y0!NnF)<6Nh?-^V+b^ zfuurCSJ2Ji@)I7O&U%$|?|!|YI;JeigZwlz?sROZcMzW^16A5RXIQ{YBfY|Um-7rjgboHI zl&V~EmF^N2Qx|%ynzI88Yed8zPKoTFyOzN*#%GxKX~?}}+1|FNPXfRhGHP5nq53!> zNl1t-D?xHFrXq+~Q@q_8C>ih0WYK8WZ>bSx#C&l1CmX7=;tp)n(DRW4SZ zg!~M?=BFA49eX^DQLEZlf|N9kuDApg#47~_BwVHHY4vx`jHh|eMbr14c|>i{Kvt_& zGkGL@ED~U}YD#A2L!whO29jxRb_^U20T36 zr zD^l*n%Cu_-h8Xo~4hSaS-yK`ZSxob4ewD7Er$1bA*3@ZARhIbimec2lPnRBN?3pvG zVDD{k#J*ksQ!-!?!@$TYnWqr1hDYq%4FXzVRUMtlQtUrB(C^32%a@U9ZC@dT#Mwpc zk9iZ2$cA+~n@0*)9i#UC(o@GOtHl9cb=$pTUXJ%6YGJKZh9^SfuCwgoVq10v<5lNr z?g$)XZ?%3!ORTWC9D)IaPEsB-9el9Dy2EhW!b2B0UrdmCV(^ihWUa?$CDDK)8O(WD zrH<(DXeYh9$!R>p-LN87FeQ;)0^sQDjo-sSQpS?K)%fiP| z;Tgpq2(mu*+TiB|(Z)WfngU%krY|4cS-F<#xqGKjJ{<2!Qm~sqpH{HGAb&VA&QeVK zX#Fx+OLd~Rx0~^i1Y>}zC_xZ|#73k+l=cxL9)mG}pI0eF396@uAI<5=#l{&BZtOi8 zt8vVGe}ukQH@@$^uRUOw#wv=^{PgIekkdP1TUMJJD83b?&J}JDZFKFu6g9o;wstcy zE(CQ2u&{TUe1>7*UA}XeOL$ zaH^2L=6qq?&6RViC>K62dPWU)*WQrvy1E_P+b>ZcIJo)d@Of9OSOffD9qL4JUP-4Z zKuLKE5Aas9Wl`+d#rYJ)4u);@$kU1$ateEK(wwE2#RGbE9(nm>ug^muLNp|k8jW5( z=f?Qs79NguOmEU2kjYHmtX0YM^)0ekf8FgSeb&x@Z@bheQHa9m&~=J+!|T2AyDTc^ zGo0nSOAHn8Gc`gQW77hvu|870LQA7k4875g++15%hlB5}-aNvd{EoTutbTu+4-Gt5 z<BTN;ZEyt?2rC)&-f7#%Vvb(%ISY?67IpiE&LpzATIXWS_6Bnzv@+q?cSy zB04!<|I0~6JJ3DGB_*{ykRFH6W$tGDd=DyesgIkfxBIo=_}!aTGQAs1xDROJ%dNG$ zC7pjX?1XycK!m|9*jyus%=!UymnP|LbDV7>=^g%Slye1OqnLKCOLJ%8-45m2yoSg_ z>W_bff(Y8!{8zKU{KWOV(qyO1kQtxxTtxwn7ALKqpde#ycbrv0FaR!XS)=GTT6UfF^P9}lVH%%eiXGJ}% zT&_K@zH?LiiDBwxqVZivk!?UiWJ-zerk^4aEwMwc4 z>~frI;4A*o?Z0`2tJ^y`fVxGt(i^NLeb2&?Bl78;g>jGo@NJG+%awiBS=4nq;gK;Mdnf_f1?2x9fD zTSE*GqapJeKA?a%Kk_~mZ7OPHJV7hF+?aCR9|q|orhXrxR=SyJK0B}6 zwz%mhdp|Y&`;|zR3`b9ezPCn=<*e*p3NnGNz@g|6%5NAf*VWA0}}3FH;uAA%it}@0x>x%FK%Y&hj zXFU72nCcJ=AHCuoF8eQ~*eiUZ=up~9+e z0?d)MTF&)Jjj<=O%cNaMeR|8*JAy_jkhV~b$iz1L-EjsCi`^>IC1 zckS&Mym=$<@OtP+E!C-EGK}=jqAsbU2mz>zYEk9SZSBN@)b%B+G+Y+*+5A!~p&o-- z8kmFZ4jeJDcFmI*zl}$!BeW5QK5je%c~q zWrO8=%Co%_dc`MPBGFKq9;Wy5kqm`XXRPGyQ&I5%cWqh5!u(vpmCKKA^~deHM$aIX z_C|$>s<#NtIl-w|xCk+MII!YFM;Xyn(z&I}c5+{R|E_G>Kq>_xdi`S2tdCu z>zfV;)K)q_$6{XcsGcf&#dA$i=02azZih*vwn#II@n$ZgGQ^T*4)czrF2NhUbS1}; zW$|r55tW5Eb9Yb(ESYx?6?5o*>#gLGQ!ZAIH~=5?5QXVM;e=&NcS~(Na>zgMc2il# zmMsmpj_uL4lW$t%*Iz9NZLKCXgmV_#Sa^!bV~7$t(1LL52cxB(#%l_^7P5Nmc56$g zhYA%xTU{GK@V%9bKP>c1kVrrYZMR%>tZOjmn4N^H!jKSB9^L?7St4Z;Vd1Pgx7od_pM86s{E`b;7WW;Ur8#A|b`bIAPa<@?_7g*fL?N zrJZv}p~G2`t$HjOu`5E_T#$AOPUQ`C<8GGd6)C}lrG>91j1r1?YMgp94lVO%dn!pAp}t#ho=GU_FL7z7^KuG(lzyxajv19f5(jb_ z@n`~@$2BPPNS6)XF(LoKc<=-fSz_+IqWZdPqR=alN2`g(SG&%UOIRe$?>^6)hb%kp zio*`7%Cz{Noip#P*yHESA3S1fV97jETjjlS+CJ7UZe&8uZmOF-f+4mDbwMQVYfrpE zI(<3Ne?MSYlH#GICwtAPlEz76KxBIYeEAZDMO{_Q13RG1*K8hu0 z^UqHgVMUcp?A~3Ptb8eEA^{JN>zG+#7`979MTbyO1YdX1oxU4|(0|~{B-*4X+`r8A zP5o}OYjR_MXLI?+fUfL|@roh~jjo5e7WG>pUU1E0P>nTq3(Mg=qb>1DIsjSf7jod6Pi%*4 zO6pxB-*J{To66520kgz;m^195DafFENO8z1Ezm9@^_ady!`ub*T1AFV;kY%g6&!e- zAC<6+?!bel5ZnjEX4?;Hn)ZWtv5I-BM|Btwd}={^wn1X_FQ+?yQ*QLDU;ZbW6?BMO zkdm7kraU@60nm;CqA_;smYq+Ph9gbu2N|eoYHpJbYo2`Wobc%YwkvT5sS)oz%Zdse zBX=|jWak6aUbKpPyFiG#dI0@NgyMoE09p#ZtvxKGe%!M&RlFYfuD^dG|6A5M^Ar@*p{geXA%b4E^zzq7Ne00VUw<9`?#nP)$7 zPD1*L&5EmN$_k%DH(>B5uAuPLlBiJ@g>lYLxCPl#`+ytTTOUkDH)NPvjzT;Qes zT8wpWBYYGzq;reajReeJh(T~Stf(%2H{nR#eqzD5v01$!4ZB(_QS){GYS|Uj2(jS% zz0rWqUV9NI4|lHu=&l_Tmrf$Q+tFc&vG+`rgA9c$P>nyJjkRIeNQpch!s!r}K5PIp z-pEf@0cI}w?qt)=7K!=I1!GdT#3td!+!FJFiq-VDnsI?be4IdLDxKWD^KQYKdd*xC z*|ASPy`;a!vTGNT`eb>jZT-m?>@K~deV$Hm(hSJexgD?UPFhGgsCCZYUSU)_+IO!u#HYF?Mk;LftL z87o~?*eJ*f*g>G_FUzf?_ATDvJfk=}f}wnBy*u&2yc>Q}DB8@BNzM~IlmoUhR1`MC z)`eauMm`bF*UQw2qnKLkrBO^e7D&3_Qg9rf5gH#(KMF9swz)SH-CJw)jv%)unqFOf zkMZ>o8x0CXbG+&?7@4?zvfexKZWvTjE1Q+pgui^^mVbAiDUTMY10`hFN2@2yqRpX6 zcX(HT`poAOcx-$=xDeiUJ@tgVz2u#T8Q&gCs^5qgQwN{Sq(DOyf)_D5j>CY=MjVKc z#A!jeoQo45$VbylK;u7;a{7EIWh;r#J^!jir%a&Sp>f~N#l<{q@0-B=zDs`o+>E#0 z9KyXS83)$mEhJHlekZ&K;`Qrc8LK-(YH=Dd&xbWH1Inmf<0BUqOz?L7wsHd38JAxw zWY8uKyce0&oxWi8a0Z+X)VRRJRDqw!FNeviDkVQ6Ucn>P2r0-+viFz(;@*cP#1LCB zn{RXCk@{R`V+%8Tmc}zavBa1D_gK$_i;Bm}XmIhe?;I-6`J^mK@-Dukba-G(+vBP^ z?!9qdBAjJ(`?M40GmK^>UUOIbrDRHv9aBe0PF1K!H-Li?kwM79oXLjp5lI*P+=2;w zv>JOyL3DnJWktI37(VME83SyPKfMGZG``zV_CK^;(5yHU{tl~^#a zLT|DUg-^M7X;3O^o{hiTC4}$hWFL#$KPKO#J9=0zR-8-pxdX^Dbdu(Q^DO)W1jhqR zojSUSw=0NMqv;Etq^=n;xI_nfHSV0%n9Q}HJ2EjQ8%J)TGnbR5Stq?SVdt%>X}dq{ z(D8XKZc7Z>>hsO(@!?hZZjxF1%y&$fVnY!eEgOeOX-BK5ZV+t!nXy5eQ_M8L@d!8+@ik_`S`hyf=8`+32985~>-M?Af zi>*G`(ik1ihL6}eUC_Xe5>XyQNU7QkJ5m)ebUNL{jP+~66o-A{fCxS0~g!Pa1 zit>e?8dTtxygCr7wj#yZ!k}_Bu0O=dut9I2Q;_U+-+&C8*knQ3@MdTSsi*TDEB@ zwt@(BQW7ZztQ^aC3&s1@)#$w_NZ>qCA~i7)P<8g`M@qufU^XtYSr8m`@;*e~*_&)U zr0R0?!)imWrP<$1CC%BVycd3I5bS*;zFPalltyX06}yd3JSSg`(=rDYxwJB^t=dJ*_& zBShc}Ask44uH2m20|^p+Ec4NqOScVzEVT`qn%f$0YgfsswT0y^XlSVxw%QxRgg)nu z_aY2mjekj4j=vu+GbnldAt5$$?#9khg0C5$nq3h$Gu`a7 zu@N7e@4l09P-))hO{FE$jsshdfo>eanTemFr|SyR-1a4x$&s^EOCxZc+wp~?6D+nZ z(bs|kl4!VY$FtboD~~LUt}G0pI7PvlcS?!t+QW+I-%p2rm8tv+IrfjFME^uRQp@N9 z@vkDj=GQvq9@M`un5bP25O4fZKJ6qBeY1BZN$!-X3EPF+=g+8V>R)CV-}A9@)MtpP(lnECw0V1y>N?6>ggKaOx0rGoKPYh;e+6B9eS} z5<3@9oz{|W@Bj3wi6&)cxyA1h)j<^Nq4$tk|A+AxjIJikC3Jo*GZzu1$h>H=8)#~xz!pelTMFsVqiGGP?GUC2K zX(Uh`nA}=1G#9WE50;>yock(a6D}0_mV)|5p8e-PgZ%m*T*CjPp5`AmBMSkZL@L8= zF~Y@&qv-Eec4IXx3iX|lnvD0(R)1(7zF5w(lX$i*ck0<-{ZhEe&d>=qpY>fF;=JZ_ z@GlfsKyq=&G$b%5x;BSi1^l^2K)mWxaQ@8$7f@!ko#V+kIg^}f|G{Tb4A%7nH}zg| zq)P-yJv^dk4?;{Tk8gfU1MIClJCxP4*Hri*S$frQBkSJZebZq9@~?8}oyRuW>q_wtx45@KA*<_68HA5f z`{%usG=ttP?s0~#DI{Qi@_+s)+|+>-poBqC`jLHLOODLuQ^xV-N6mHdx&{`ObC6Fh zjZINjK~d(7Uc3rlC96Lzg<1^5@;$LII@W#p9gP@n0G!LEki5!iA4lva))Z}c&XaFL z&o05P{dn^wf5a^GZaLh?b)l&yrJ6ND_^I=E^2X^!32~L8^lvNVA(Dc|ietaLamAE( z$34LLEMnb2L}gq{Jle| zcIt_qV1QZ?QK%hk|2Bf{TEIGt1j40M$R{3rH1C2~!*&8*)VJ)lk$WfhQHTkCd3 zjh2MFt;(@S&Z^GADSIc^c5y}A8|=lh2?q?w?!*mFry~>=hq3b{_~pvs=o4+FIekBf zUWQ1T^jL*#m`QW-ZRo@rI+{~Lp z9RQyTd{35rjuqHyoRTznk`La#)$aG9xMa4gt{4i}>6rH2G8k1G+glrI3$KEM{iZ*t z)15<0SC_wl6|XwVzxC4mz@dF+HC{ebGlcs7>wpv(oB$}vMn}R0_GCT;zmhKkX2Z?n zPFuz5hTMB@9I?!Dr3k|`yOUQ8&1`l6!k(lfdG!H2mz#_Qk9K@GXxkosG`UrF354r+ zBfI)Z9^|q7__UaW6zr(Q&>85-Sm^}eJciC?%w8KE0!j3@1m>4wJ{2?;^2y!<-9xBP z%NOzFq(;_QMrhGGM$VOxR$33AQ1##QmOf&!O=oS@BaY9J6xE<=6#Iao;s5&R`=2ZP zpY1R6N7$K#_-b6m=avee;<{5%=~8n~7jlxyh%vEZ>9c$RX=#rXh+45b z(y`7Rc;Tkz1XqFR5xa9##pP>6?I8=`K^9ISYx3gFay#_cHE~Gws z_?SjoA(!>cxhoNNtY;{0zScJ}mDZ$4ayq@5_pz#593t=DG2!p~lB@}R3X$~HcINzi zj}V;PRF<+gkZM%8V)!6=(}3Hz`m)xw_#~FD>4#_&hXBub-o-&G(zmX)#azWtE+eYl zWeC=74CQwEeasc*y-X)$lI+avtNfpc$^9A9B*8NDJx-&!J;WRe*G!SRr05XKshRrW z`iY?Mtf$WyYwunk+to%0ucYf?5l`S+4cH97fRs=|p2B%cUeE?=FFQSZzCq^W@4=A2 zoeBL9|MZ{Oz5A2@r11vV^Q-53I1j7d%FquekZOJXYhmh}V*p0R|NMd6!ksiKUkt|` z+xE=HUVB+@1;f)p0&&R4YS~}0w2h9e%Wnhp{C7YRdciIu^RA8543ZP*5P+4KLr+9@ zZ^uEOr_14}a~j74)Ax}B;xYro7=tXoxWc}cqss-~-?l~!(Q-FEr!a&bdyHi&oV|rj z1?6Pyq1oU32;Wr+wg@>G!)xI18WSQ0E8nj45O=>)Y%dqB>Px`xL#qf3X$J(fb@aA| z13f*4J`Iz_L1}22$^4+rhGV31a%I5cw!3CQi$|mN;HWHdWN{dz*F#AE2u{aCWv*=S zw-9*ufF=NR^ebY|>W59)M`t71EQj<*9;NGT!NMLkWwU*+-<{MCsbKedc{cjxJqjTy zMG1zBr>N~%B10%%G6ejmc->!lg8s>E|2tm()6>Xb?TpnURQ7(h_$UNj%k_4bUL2a< z-}Pi>Uvuc;pvMzsy}{|`NA??)yi+v_=T|F^a|~rkW27lSx)zzd4L&AjV=v-cQlx*x zXq#`jn}~@q3VS$eJ5ljh-`Awl;(0z7P;10}Q-M={_x;HbM=_R#_iMQWA6?JX-ymp3 zeaTr%r0j9=F*^O$-Jkd28N3d73WpRXild!z^b(sApP=sAaf;KTW@ILuVdQhhy* zXp)hQ$N@w7L-}}%jIfh2w3=vkz6Tg?it{J{E=Zp))?{h&HtOwa)SJl6Bn3}(0q^wu zVx|_AG<3c2uTsjtN1P+xVR) zpWcBkPOhZ%RqBh){l2sK$i? zCJqdb>(0&|oY+UN2u&YFCM}rF1b+^k?P_&_*El5;pRJf=KZsGC+LmsAdOMLfipui# z<7By$hENd#t)v8(m`)(zdB&3`cUI}7h!y~VT}Bfwhl zxb_a~;vu}52D8WGDnxd)94k#ET!JD?nv;Yn4K%NzW9Y-W>FTeuvle72>9M}a+n!e7 zWb&$GGQOY+u@YWR+sUXn4|sP&V=g)+KDl!rx7d#aEc0?r0h>91%=xOOO&T{Y)`S$> zJeo`j!wtILeAsriZ+~Xez<0l)@Ur(a?M_<>H7~cu%}9=wt0&J3<=<`QbEhwx zKs&rkyH&o;M zbFX$;9;M(6LF$*EafZ zWQID-=+sSiRoRP`dbB{-*)7`URfIi9`EGubq&Qv|{4WOXXviO|*1L(?+T<$wz3%;X za`-i}*8xC;tHo@SFCOU~r>v0D0W_?B{*fuHglsSlXqk2&Uq5ySymF#}wDu`5Ki&MP zkQt@|5W6190~X>NKpb%-r&(9PQyP&QuK^bwh&gi27KsDF@keA}Ahx7e{0qe=UC2Nn za-S7wS*34SV?@P|sv#5f)7wWZfCj}PsS63nbKYNve7}#tTh#*1!1YH*>Hq$i|Gu05 z#I?Cce~pM5RPmp%Ho;qGJweE=GmK1+KW^jS?<#O@cxmJmJ3Y!neQ)E=^h<`7jMmro z-D2#C63RUnU^BdzU7-;d`S_IHQGc_C-go({kDeWR3BXMGK3NCov{jM-c1as9QR45H z8UIHTu)n)5tY!b{tDW*0Aov5VluHOQH_T+{*zv#wQVw4)o)Z;6$VApa=5GGADy=K| zX%IXx^u7(pz6UPcBaUXxuO@F&@6#VkXNQ%L33B_WACbzx^6LJhZvAh@^Z#*i)c<-W z{k13T-&>ejDf~2e6mB7{8k1eGfk?MVb(u$_-(JIkvA~4Z8#C)|DYymv&5Mr&%HhAJ z);22;UlLN&0;V|IRk=AKa5Yyvn`VG*Lv)noDW30y};^4wx>l*nV@A+Gm9&jf7 zwk*OwvRwc2-~Qd!KOH`J6#2dfvA>q|(Fk%FMzoXK&!2xtF8GC_G}*Hex!^#4^9zL+ z^{;Ha|C`4j|I;gd&<#N4Tmt5$XMs}q0#d{Q*6^bmGzr-ocfXweV`y;(^o{E~_^r=> zbDcj~b0JW~FBE3^cn`pB%ouBZJOhr3?)-(~*R!kN+zo&E-u=m2{e_qRQ05$f!yrhd zi-bgL;_GVo?m2v)<0ho--LdK~6gmP+&hU=mV=wYDz1# z6YE8!#PJ{rHo$^hX2!&hPQ!g)97T|`blwA*A2j=D<+z6vm2v*BIl%s>gbj%F0XJp2f^Md7VPhkdF&Ph|Ie)AIxV7M@#z+|#J%3WX|>zT6VuCOyB%Ye-v z0gck5m3dZ1tTQ2rW*mzNjZf0xvX3F@U7oE3&f3yXy-b4#DD6oS^5vN?F(LbE%=Fjq z4{#@iQi^=6+fK~Wj`JH>z zfnY;cKc&%OYqYXd|Ew|Ay$-iUb(7RFz2&<71gZG=D6A{Dbolhk=3EX zoSaUnF)x2Mu_|Bhc1@xRbg!KX`A~QM6yD_>cNV+noFQJx!~DRbuC1tU{!9tk2d1}~ zr#}ryAr!(~pb%5MV7k3i@H?D2hmT(CxU2nbb^F$?XuszI=dLnxyekrq93=EV49U|e zgfh**7%W%O;}rFeUeBi}drQQxp5yYN@^Kt|Cbt@tQMS5GTFqZ=!Ih<rwle+a_XO%YPWAuluPTvD=8y>;SepS?Jz6w6nps0@xp&f=Poz)mE31It$Xv4$ zEVbF#2c`Ep8ovQaQm^|+n|Tc3!mrf`QwDDgg9X(|OFvV9$zZ^=YzQdvU09V}1<^yZJ}aOwIWcN`g|4SkN$$d@wvTj|wYo*~sJQNG zT;A>6Sk~k-dW#NX0O!zMwjQxVC3BpYV3bFkA1`V>af1y5%RVY$nF}r5Ce)9PAd~Y9 zNgqiC1drssd8uK=nnVw`O7cT(uhNgjQX5{M9$#j>DyhZ!lD^7=_OA1Op3oG>-8z=X zo^KO{boGz?Q)t0wY!tQV(O23|9TDGDcFJgT!=9FSLbUGkaiMb5D?o_sX1p zO`|)aFD@v?{|r@hv+~n9@-D$JnP81?6Xz4e+9NYn3=#N+8)sn;n;UGUW$EOm-myhx zZ}c_5wzrOv5jCGgkZoLg<2r_0e)3_~N>>n~AD54}c07!IJB^hNe81gtTFgPFaN6RV zTX6Z}WEZHCCEhqKb7lzU3Fri>Y-&%;N}IAlOm1@D+W-~F?pUadg*Q3+l)gQ0ipU(?(B^#0*bMFF5LJrXT1lqN(sA=jn-)s)^ zjeHZ_+7V!1l4Y$ox%U}y)i|n5HF*cq-K$d6W!l6BqVcKi^u~3h zB&p(j0e168=e0pU`s$C>vn9u&*lGOupp@LTsFyh`#qrmN5Ie8wn$@XdBT?SA0u+lM zG%n=t-@TcTewFzNTJYOD$&Y6|vu8^m7X}r(2136vj!FYN+L-8Q)`r*F#u}%%LL|+G zze(qFEo{o_KR!5b<7{)LOnTjW>HVaaCF*YX)MMJ~4tZArBT)6$vDkp)8}7<7yyyv} z=v=M}gUH9C<*(b)S3s z9o^^N(RYkffA*>^Yt23P+H24G%xBG2^pT?}p>O3!LNFA{h{_7vx&~7D8bV+$8RVK~ zq4`g!zGR6ED@JC#}_B_~6d!;3P>#EJ`e#rO`cp_r$B z?tSzd2|49$JSn8zcd>`;+WA?EF_g_itkligfWp-9ZT`P#8jl-%@w+@*gY=U?!#X^B zBuQy*sU6!UP;&3DnWRtbs0?*(8aJ5wx>Owu_fH0zF;mPQ5|I}Hw8lhEFGhVP{<6F9 ze~}HG?hFk%DGu2n$xb=TqbfZNO*re}&k_)kNK8Eg*rDGpD+>!N+W=ad-^uDP znWZcMTdVIMcy_%|Ywst?uOYt_gPZA#!Y9f_{rCHRo03o`N0j>+Ap0fxK~w!1AhHB}i zlwobyc-LUeZ{!WV)hRhd2;8Cv8kP&_{MNxVn_r|W?81~%Roxm1_i53h`Dve`kXrAi zNd`Rrnxj7iOKwZv-hMM0QT?S{AseG_Mkr__!MJ(WVmqcY6HGxYcZn9ddUs(m8j*^= z9_es?uHQxaT}GFcrX%r|_`~NX$J-}Ij<&UJJ0=gV5zpjp$%K>oN4BAsnb~G57e+VF zHqKj3O)juPWZ%zsu+A)vZ)b$ug*RH{5+9Nm0hr1IocoxJAkg~ST?r_uYn-pt6_fIi zUDse_5Sjr9HRAPRky_KCqt6l_bmrqF!%#;8bbVNZp;IBqY}cX2#cI^H><8eL7cF^n zQ@f4G!+fU|q3R%(*eK&(R-213xD~E=w9+yL!@Vl>e3+4CGg4kHpI-^f&X8o+Kz2S2 z9#=+=DvJgeq5rco$Zg(uFy175^?UTp4B5kvX+O4#4lbcxL_0s04tnoIh!s0YiYgf5 za7DtgV&&PJ$EB|`Ex!7Nl4SjnbCp&m2eF-?8Lfug|4(u1`xHnU;_X`aJN0T-xJXXHa3zR3G_ZKLBvx zE_zA)p#VB!r3+mGzm%`Xqtg3AB^guFg4AA|n_L5Y;FT|r!|F2GW9hU`Uh@wMOK76r zYX@idGirO`V)e>UJ8)sbG%ZVYaU1f$JTk_m-Yy+i z^7`uex;_~^*?MeVj$eSMpx={Ji``KYh1$z3=yJ)n)Dtc^(1*UbQXc;S|AAGn7qyb| zaBTHtZE|<;(Y-mIwwvyK(D~W9geu$obkIQmYp%Kt3K*T9zMG92!pPWY52M7hA&P*} zloUJ}ljAlMT34Z_|&Ai+b&L*GUJZt}xc@)mW=lUCNSz9MueXZBt%^S~VZ)yC3& z4dk_WdLJV>JCuh?)z+vHNBNN$Bo(b0>r*QiMM;6TI~aMcLB!MZA%GncG+30C^SwLz zy$`7bi8P_suVTgS-WW=EQ%GbkZIz!7LYN5Dd+JT5R8&3SV0m|)yxYHH76LKc)}yL? zfR6Sl_`5r(DU9BQTUnHaGdVHpb9NfijM**Ct>gsm!i~(A+(zN`VsUr5swi~3{ow$I zcoRf+QdU$9ZNwZOLUPd{8E;*FilP=>)?WV4-w=8bm6~OEC|T_RQt;v0^!c>?PQ9c| zmolp!H-3;Y#X+l%5mYJ<(LrCsZ_t_M8O2Q(g(;^lkjkq&pmVBGIOODt2`$flWMl$( zDoO2hMpAEXt{G7pN^_s?NRfZn#+oct8WPTBpfJ~tU=?=e{Qcs57y542%Z93}`w;nb zr};r$4YKV~3I!-*V>gw_27Z4H0Lh#!czpWBXXRo>na6tJrZpQ*EKQuA z=V&!GBwFJvB6I+_-*$}35_~Jd^)TP#_`-!$wyr*&zfTo?8y^Fj6f*7(@(P;lg}Z+n znxPV!Bnti#e{;;$wGrHrRc|*!P&p>s`aO()vBYvQ2=~?b{L4xkEY=*yr(<;PqZcD6 zQ|lo{8$Si(@;^ys?VlmXLnEI;eH)aQ7}$+(kdH|>k0ZOFuT&Qbh$jXa{cTrA>Uvh; zelfaEEM$C0aVJXh!s^M#VY?j&h8h5Dy4TF|r>R$8GMprB+!TN8G))ALLi1@Bu-B9Y zXfqw!XPc?Vs>ey#)xVUiC#TRPqQP=)?_rTJ%jF zN#`=M#%xgslXl1mm$;zv{jW>)hm42yiEFJ%Luf$!tuTF_gd{OnG!`!lmc?b67=`%E)nliSx%EwT? zxs&z%MyH&Rn6k;R84;JEyX@G$pPu&TVp2BMpeGM^gLG&L2OpY;U%u{T$JSq@42F;l zKuZSd*m-lAV|=r17E-XwquwKWF+F1=g~#ZrPcvQIHD_HxWS(xq<_*@xTSW$Nc=qAW|i-{2HL)szL7WfRH1;#%Ejspw*rWrkI zj{VM;p8;pk1+QC}J8C+5&Y%xt^Jxn-GRJc|1cVHZL;4iQg&+g_9lK<8l|#UBtMTD` z9Xmd-XsIuF2H(ER2w@paPsd$p)QU76jwvP0o2NLPCqtLVKT%Nv+Nbtqa14Nwn# zd4PWT=c|8Pa7}jGyHBi5r5)SyPtg8zr1fO^3|Qv6xO@h@T~=SaD0l|2`rR=4arm7O zKs=rSk+$@w5LLgFj(Z%Tw2s?14{gtYJ}zvxhvJSAgU1MxQG@$WPx^kF1W@ZwZEXkm z)El!?`Pl6T6grRU)q|!=vAe{51{n2UYCf%ZBxl|A{Wb{`xgZhGfNEn1H0Eo+Haz}d z?4bE?DgU`HRZ;1D<@EQ6eV~IstM@RZV^?wH*h%6ChXL~k*C&&ZVb|FP*R+}0FK(WD zX*eNytplg|I{v0^uVEaNw9?g&?@Ir2IPiZJ#`+5Y`2Rp^`KN#Xa$o}b(S^n-nfbp! z>bF*O28jJ8vve*Bnr26fEvofav|8&kdNl1p%M0?b=Lu<8_A2jO&x%GJLP3$Y7(qcf z!lYp+Vwz4_cqw6TN|Y0%NYRX0j7f!0!^n1_@u$m3gU_WU7Wm(4^F2bwoglvZc2|5r zen{)cH~Xr(_IF}#u@+B;)7MC9P0@u@DdGoIim$MTSqC<=2tP8Z$_wu`xJtp%TAy~+Oy z-aU;H4dt8*vxA%$y=hqw!~cQ?x{RFLc13duBzJIC>ycy!x?o**p~vS@T+POo=)w|F zJI2pqzoL$>ZZTJ7${Aj;pIn@6q~DPjRpCc|1)#^l`UApPF#tan$FU+qS53|p!*%LY zUK&%F^oNI0rX|0L;5&3Jr(AP$MBZcXu~_<)4d$Y`-?Ur#^|s zK7A-{(?)(0_%*t)&j29ieq^J3P5myO`Kefc0_wHk`B6LD*bV!dK~tg~ctVXY?=SAj z-;^$CQXhINATi358RYS(3Vo;A(?IIR;7Qd3VFE@4k=k4kna(E>kbB_a^-IqgORxR?!t=2r9w8GJIW zd8FE2<=y(0l6+aLeBzKA$*ou7X0!!FG3SG;$o7LE^YW`mIa|rv{ z7!Ro>G*#6OF(&TAhUAw0RNV@a@+AMnjvs@C$O4mh%#Ix&q;Z5;@59mEBbcsEUPrTa zYA2dJT!rVoiAu@4dDF|(^t;`I#Ltc|CAJVi*9N6d2Rl50Hfa9+=m?%h0Bj87swWb8 zPuB`!F>7(_>kghL9SF@O{BV-K@}*fYaqjjgFO(EBedJt}pE<@|;p~-C$%ywRFSZJ8 z^fimjIs3-S7^5-oXVU1`*yp<-{sze#b7Em;ZaVKGcOy_kJk2uuCiB zhva!Uo}7-Sxs=ZY5qr*YMCs_wu8v(!UNf0b*INy@7H1ns%Q?tWP)f#yDYafCP<=Ns zZp3moeTPD3q+jwY-yuqBIp|&R*-@7gMg`M>uE-!ib)*m1RbM_sXi+LLId`MkH;IRD z7a`jXiGDdAK&i(!1(s=j`IQDbK1Lh6nc1bw?b}DoCnkv@rRqBda@e# z2&Ox%hn|E|&Uq|nj3%jEn`DY!E9j~STzmyKS;I4>yvl|eubU8oVvi7=OQP{4JBs8{ zt`Mb5yJQ=ecB84`mfoel>OqGR56{&b0s0$hbu6h{oC=eTwqb0n3ho?=PW_BMq8_`l z7mM%_v&h_1gZG`P*EDoI^1~SjYve}Ex#V04A5x~v-g=@In#>+vkX*#yU$n|Tq_kh? z)vs-T3$}r42>vS1F+6C*WOeOPZUprJKtLyc^pIe?;M-UogE^sYR>7RHTTE>a zzr$xhF5?bJYLc>H_I!{q(j+QzoUybk%>UyuiiR{R5iH^=0QDU@DY9Fn?@>yld(FAG z&b3zDQ$ntq8IRmN#&wvkf7~^|Kv+v_ao-gOY#ON_oRk6U+FqTO*lDGuKf2ZJIYz_P`g8cu~lK9`h_Fqjy`Pb43{$IN3 zf1yG6Z~gtBy$1i*-@o6DJ;grPFgGi8z;TI&ClJ56qIr0$^3a-OJGe`4XK>5iCdQc=2|A?6S^P_^_ z{^m14ZNc5Ma<}^tO6Mtw{)gv!%hUWyhtf3rpNcC(N}jxhCP{u3o&LzWj5UBbbpZX& zf@eC;EBbpT{ffsQ`TY*k?*3ij|ETYO>+t_C-6s7>7Xmc6NYC_`ZkyT>5E_BTi83F$ z(r&U{@-5=`aqLs-GWevU-KkmRnRnJ!>`2$0EVu?p{764!q6kFoO*nVWiuop zDK!4k(2NbolbvCtic7h%S{XPm5b+oe=v2)k?eJ&>}h?I*5qz9BYHL)=KpY|#l zIzlfcWo2jM`rD-{rcQP)j>e|HD`Wj*kDarjvneSHP|d^M6sTlqZYn7FpQ8R2;ZIRT z>>N!@9skxSiylzS)XAAvo{O1>nVW}&orhV<)X>Dj)|{1D%+T48+1b(1*2%`g$;rab zmf6tOgxS%~#Tj~-4ya;k?5xAe!o$o4BIV>@XXXNtvaxV5vvQJhazbl^-iWG;k@Ig+ zh7%f_qX`_tUp_nu&{PEbp%RSLmL${ zHMTQ>>c-U8-1!438#g-C4#Bk)r6k_3iNR^^`L&7#qOtv>F6s5Q+ew>WMn zZTO`tF*iBK1{i||3ZbqUo<7@Vlvv6*MFfhYz5ghVHXeIaQBpBnEIW=n?k6=m<9=@9 zao+2woifchhwGw?OP&3Emt5xTppsfcYn+w3eL{XCZDRyomSWf51)WCvV8k)l07QQN zwBd4f{KGXDZ?+F-!hVG)t(fHIW_Npy87DPnc&N}!I6+T+YRr6o5DVun9}DBzd(tK1 z)S#W+B|gRcQT^G5%XS1x%$*Rl<-6RRCmOjlUUPL_Kj>+0icTNhAeTu+&lngC!*Ftm z>ra)HRmE~pPvCLKsAMkTl{Yqw}tZ!uwq*DEvC+~(U9``YLWhlfZB0b_+cvn;bTz#Fi*ja*O4pTD=GTiH3z4X>5GiZk z9N(W#F6HRMMeY&ouF@KCt#|L=0zvwmrH!8&BuB%qK1=qj#z{y_&K0n&aC0Ot`7WcW z&!P?52|Rk4&`ASYzs?Y;`a2%H^KXpljti^!I`Or(jr24nQ3KXP1-ob)23OfSiGYwH z%3cizjs8MdJm+gX*7Tyd^l$~Ej~Z3J5(Zrym;N|k_BHI-Gv`qxX6#7q zh1S@YMOkx;44GjX%64uZW3S1e2+p5r5~DpWq<+?Fgl2IVAy;zfPCb+dy$m>9!A+-$ z7;W{@5-9=vB&$d(H>W+~?>%z-!eYd)I^&P(=U-IP1&AABB5&pRDk>wluxQIH-L^&Q zWe7Ivjf?|l-EZPNLBZd>^c(;%xb5mu`yRG*)(sV10J#^9I1~kxyI$Eq-;;o>T}Ijm z|9mCf@6-m}$6o{DefPDTspwH3TPu9z`f9GQ z&Am)4QD1JL0by?^urWkY;Hgi+s5pcuIj>~QERGfPROAg5=#F1S_`vsIvXBUip;ehZ z>6)lfJ>j2wvS#L$Om!lZtmGB@5W+vVu-#!x zW%5JTQNHg761?mHCCaJ8OEJT-A@jsG;}}cEeZsL6NrC4jFo-f=4L}T7FNcdn_n&`F zUEnD~k&i#06r8GTIynAWFZ5 z!3@I~R8+>UYlo{V-|s|^>_#x-9>7rGRHE7_w-{xZUFItLswCs^LksaD?Q!*m$Cjbw zYHYz3EhS1468x8!LL{5A<`qUDCbTi_Q0J)p(Ys zWUc64Lg~4*7nsST#M?D!#M0TJk2ANCr@)k8vWbCg9*cNadJU;TVmKypZR1|wF{Um0 zFroZke86xBrksK=cNoii6FriHsEGTFk z24FEOw4CuCEDrf;M42*Pc)+PbGXo2c?7@Io{xNev=J4sj{ihLU3n+fx z4d%cwygkUWBrfU~>5VCew4T5`yo^HyV%VsWY=XBelJv>XpT+xIElGFWW+HlEz2Jc~ zBwvz?hq<%y%r5^T3NqkFe7HSX9x`3)G|AocWuIfFCev;CBXOQlRbc@r5v>*(@oqFEPGAKd*YiGIB2(G!Yy0S<#Z%tmBw*|H z*Ggr)@C>m=Br@pMJ{>W`D*`%;b_b_Z^>TH4(+P`S{V?A@Ls0<{ctv`wC7{E zoNS!bx832TZ#KSrzC5m8mPqs}lQi_aujR86G2-?C;8eyzSL4a7}h&e*dD#E0PtYPYosDVw)T-(#se#ROT*Dj3{J9N z#xhDeQ7p^_Suh6D>kG14{UTm67HFcIYvQ#3UMs6)w^}tPFjxhw+~V;_7&Z&jE29wE z_Den}i`g@}5&O%hbGQb|J=YYSvD1TG31|jgg zB1?dqTcSX%)WCtJWGY4|P$RGKJ`=+;qvvM%<~y~p zEBY7yU%vcQ@pS6x-^d@E$0;n+V%4L7n0lk8B7m7P4W)KlwPAirdZk^=7C*#iQ<_hm ztZnv+2nspeUscmB@-LrR?rXb`_=&c%2j#5b){_(Lo8%Q#CkzUh9yA-6n`JJf0?jzm z?Ootgvx~(?r~HFa5U0d$S1T09cFgi`^uS2$UpvbQI@`RPk6KtDVIDceuUfQKa0_2^ zVpUmGsE@iIE%rxVc@qU0-zFN-Y;WUQ(89D$=HO;n~<8cc*fa&MYpK zNqV@8hde%x5;(G)z9o2P89R|6x6aGV^Z|z9Vqush8T_mYQBijDwMy`4tZq5EO^Ne_ zZ`3!Tkt{EA{KC%Q(_4W937%!b=*h zp6nOM-raYSNOp?y!-fR7U};?NAk0gE zmi*Y5>d=|o{>Q?-(>))0H{pkGrm$!B{lTB{*l@nmX(?GnqhldBL^cIPyz@Xgf!X)= zx!=eaB-m_-Qou9`B3^@oJ3>(XPG4u>UD^9${8~HIlfIG#Z$SxHk(FLlbwm^TcDZbm z6Ng4{l~)l`a(l8hOSS4zX&!9!7=>WGl^1_I9XZR!av2jwl*1$E33<2gRBY|4yKo9S zMle>NjzzTptGYA7Ybv)eiJh&Y0Qr)yk87*8xzL2SG7Gq2;xEpJgJ)`-HPd(xfmAUw zbP<*c$VkQrClNQO$yqQrdYTq>D<*ITPE0hm<);*^ahp|L5zWC6XDZQ^E0b|Mbn^6esn7PlDYLg)1~4L&*46ESBJ~eSfvjlekTN$ zzMK(KNcdhrE|Xu=%rM%${3MxhK|?3^Q!&}hpj*i%W5~K;g~KTPjA1M!>U?)CPhnlN7VR~ z9EAP?;qN7ve|B6w1huS;a|<#J)`So~qhg3dwz7l+;hP^TKWr5aMh-R;Cr_N@&)4j=C^b_)?Zm1pxCglcRinN%39c zC<}LofklSVepWYGNoro$O(N~5;fAcZR=k$4r#zb9&{}5tUYPnfG;i)g^X+ zpZ07*BSi3wc^%#lpPhn$EccE(>VYc%3~c$ESpNjp;QS4?u&{A+|0md@YHez2&ujyQ1f2ea zIY3Zo1xnCoWoKsPCS?PGm^q>@%}k-dld&nYnxT>Pe+mc1V4z43h=q+A1R`Yzu`#nj|FLp1 zv;Q^R=eH97lup#n+Rjnc-q83r4kPNs%0|ioy^3KL!0K=nW4K%ip6nb>OA=r9O0@waOI9 zNGrq_ft{mvEn3VpaoCl6@eKMx?;DYQw#*Yj3a$cgB+AZA9hjR^&5EaZ{&eYmHSe;E?3mksp`YnGzYUb zf6*(%Pp3ixzPU3xxLq4xnRQsh*BapIh~0~NS@+qlEoJTaHK#!snM)Zt*vgJd@YxI| zGCrN0#1hxVHmv}u3L(z;bezl<=E|2MM3^~Xr(Vb!n~Ptad?Wdy z_~246l$L#*tY>HLkuGj^xh%rx!roXNGtxEYoi6G1MZ8sS3JAX{XJlr9uj!&)w8yA9 zkvcARwXA_id16Cch<^2{L-LET_8m zTLh$1yvlDGn$W0wkd*ymeT00lxQJYM>ilaae5wOQM75x8 zRZE2arkyaVN`KDwTiMlBL=Z!0arMgvwf8%IWr}AKL8+v#YBxdPh%(_upEk~#d6ZUp z3JfB_6 zUT!MvsTuo<6V;D`#d+2iwLEDee$EmC7>l^4@$`49BTIn*+S)a%-l6omwf7vB`F~E? zmE~g?ytEfwY)0;C20diN(K-=4Mtz&%?qhVD@6PCr(UC=e$r0nF|CGFi>62GwjMM(a zu@mB?Q$PqzIVI0!h%UkMb*IcCTf+h%hJ2LQ-6&m)GId0b{~>y4GRJpWy^slBleh2=}Xe@Y;4NRCqOgG(8pZ!p++1kmfqT#*7I|~9{^t;jAhO?4 zAI_&&W$k%qSJubia+}q7d=FvDQ~q+_!vSsW!HQ_Nje(4&b&e%oCMpIKdxi#%4oZu4 zQ>!lA8%OnLIVe(2{$gURRp$|UA|rcBc}H~%z+9P)9Jp;sCUQU64H zKcOwY2@Tb0!hZf%^gh&|KTnOaG>Cx@LtG%#^JV6JVgPM|H(5z%x?TZVJzL!g`) zd_o;Uz?2xsu5+J#SM1cE(u9*zAeAwko;zv>dAc}nH=NCHP#gFeYcI!YaEF}+d6#`- zqpo7QlshNz4Uq%=BBv@_lGB_`HpWFT6YL(!x{0V2KDTSyJN_R--|j#MpK;w)yf$x~FkLehgQVeD;faGW zJ;~L%$ruCWM&NUu(Br_`uN7IoYxf4JKAeFKv1DEhvxdU|@~NSN7duE%C{U=1WsOl& ziD!Hb4pNYg4H*m!parhgM)`Wkc7*R$UL9(#Q=COEVCjn?d{vbs!K(#kw&S$cT`|L_ zZn!z0*lDnTH98bh0@%>B^79Uxi|}0buxMbJ%lT)q>%Vl>(w*PDEExX$IyKH(K%UgZ zsOlk(pAIQiEqf#v|Kfx-fy!4zlj;%>9JxRZ^JtH8yA&O`?+F=G!xK%rv{O+_0`a+U zEJdhS)3}cG0^*9T@CQEg>$te=>}c;) z=eg{yz&PI)%hacL&oTGjJw3Go(%=CzFHa%sRqeP2lLtmb=?ngln?u(-Q9}8jNP<6U zDOBD!XcP5Z-EIjXU34a3c=zSM^yb2})Kg6|cN0%5Ts9DwH400b%-x`dynH;;)FtI5 zr|OB@&W3s~xBdw;2|w@#Ci@ZRt75R?YPiUuYdysFTa+r{yMbjjma6>tLxMkyEt`d@ zg-wv7oxb}Oq`=JM`-*~A*GXG+ET@t#&2eWz?wCq_g#BKX@OiiZuXd6q7rEbwkQ4XU zvvs;5d_eIOY?pLYt*dF+U>R6e2W(%>b>Sg0{Q`?E*+7EGOYKK-rCMR3Z{DQ}Yw-wR zyXY<+>yQ*xR~{`6J%IutkODj@V;&r)dX2TDVsydbjN+5nWfPyGsv-09It&Sqe#`mV zs))DheLCOhIJPGK14yxspXV0M(bOHNzyFB?;q8yxNoCsgW|It-?2MH0kR8hLB*n#{ zIe%_*P{Jp_Ar+R`O2gtySTm~agvpm(%F;?KotgRd?=vV&bG~NqOm0U80Bj|(4dt^Q zzC=sabD?a2b}DN{UaU#)ipoXTq+Z<)Y>6x7qS}y`#O135a8M>Vh3Q-b^3Hp74)Js7 zTnhJRg|<{PurI6N={OyjqM$oVs2F=xBEc!>)sWqgW9;vO4@?g9mCA)aOb|%G`AyA9 z^pa3|9rSC!x-y2UI*$p2rm~ZLp!dKz-7uY(5R#6LkS=={@be)rW!j+-FlJQzwk*&; zV)Sft?Wn-L3XeD!582=*e&u?1N@-md4bRTs({Jd}JF&V^q1(`ceA)UE6gwh7tJE0< z_vLdq7iXyl{Cj!dp)!U;25PU&P)O3qJC{~qo)%pWU&5BRobR+wRxL++o-v)CzYZSx zO&q~%$3eQ2wEJ~gUPQOBA@*Y85N{2Of#+o1oT9hitEphmoYn=3wndJ;7(6E05|E|p ziD@>1nd%pfEv*pq;;bDD+7pE75>Xpkl-{}TG|3e;4fa2gPceJyZ1*k{>}VvZ<1R4| z2Gc%o#rrMyG(4tKAey2XNt?pwVgw6QU87&gT$|;Wk)VY;x?)jD)vWApL`;+Xv~rtY4}PDjQBCB;n=Up}2{IEVh+M6oEGCPfhMjXd z925i6sqRiRat_xOdm(j+I|TU{Y3i=Z>rfbIIfASgel+5kG0;Sl;QS0>pe_VSeostq zOQ23K{N85Od`^!fQxR)BCg7%0++rQwk8;J#uKr=Oyy_~>XN$6VcYba0ZvXC6(h7y1 z5A%0vo>gvGVU9%Ebe$ZMwbci)&2^5|-5Jx`a6~oQl1Z@gcf>?8%sjPD6?tW+Pv~;- zAk@YCdFxgxWYy#&GzEC{gqNpXRYVTo(*&h1TJj|3a|`4W0IKTW9e%>^|i%qOzWR( z>?dyz;#vup()56yJY0%5g+xAcMhFPvEZ5xtw$*1{ico z%c#RfnT%PPoFad%-Y7|EO|GF&?Qe1dbY zm0D$Nc$$FCyxp2^O-vIyK@}Z`a;Z0wlxUg50WTG z-W`jx_|hxEm8+k-Y{!0cOx^*ZZrzp@?p8>jXlyxVnNvWCQCmuI{1 zRL*AMdb^FWcw!#nPOFt*GU;@hiLK9RoTQIopvDk~MsA8bRYiMR4F1r|S8?dKu_l-ILI}E0P{dRg^=zi?wVF<>SSBe z6&M-g`oq!hI2}=+?05V1Zt1e+PEMyEJ>0A4)KK#=f9^zP(|(NNBt~72?%Pp;)zl3` zAu@c4K+k1;g1cnv@GaXbXFV(EnKCxyb;_YxjiT7n>b}dGO6aEas)|3d&ZzCNa2ghj zfS&Ym&F(>zt*gcgP4S#NdEi_qGHwN#@i_;7hFzU~4vCPGuP@oH=#QsTTc+6)#+|mf z;jt*hV-Ctf&SlTZv8(lUv=e$s>pZ)DK6$x*KlzYY?b{<$&&HOo&!DP_dwIR=UGUd? zw^rnKyvh9sq)%1kJxv-NFrt%5#qXCKF%RBNBv@s+kQsR4%@GTM_xl|Q&oiy)1M`M* z^SmOD7Ywt$s|9TYBKcdkEVlxPE((QZ$bV(wx+Kw6N*7q|Uc7`a2D5}nc&@z+uFEaM zqBNQ3z3^La(xp9<{RG6de-bwM&{C@H3d03Z=q4qm(bR12!i+;>`>-jMQ5K#TqW>v6 z_B)Zt`o;RZGstQfjdcET=HbBHx|L1yort?n>X~F_UQl~2zA~(7gXU=m%OkcNSfrDO zBT-oCa$nqN2;YO9?R}%!r_+a5KoymeTx_HR#;;~(a+2GO!xa_ZkSaEtN6OJ$FuS$Q>j~VOB~$Or5PLnI9QeIN22dO7O#MSh>F@YE|Igk%D+~MI zJNE!EApaTq3k?kg006G8uBN7@si~=IYHB4VC1hk|D=RA_BO{`sq9-ROt*xzSXlNi1 zXkuoetAF(8=1y)|-KV(p+q=8HgQL^)i-gRg+UD<3$=NO6`v=FS((@~z;v)X!+WLp$ z{>CT%1Jki^c2Y8Rgu*oTcDBEXLEKQl>py^$|3FZH|KO&iOfAemIFo|dK>xu#;pXII z`R`nvzdb73#AQ5eV(KY&$&7u$b23gTyn@;ofEQAy%T!S z)=K8pJ3n(xK(J`j3%7I^!l@qvIy`yQhWDGlNNHf_M2RDhW^-6v&ph4h_{!f_&EHX{ z?2=7p*Z3Ht-lrU?BtY`SSSCv}pyQLBVM`z{{<0{o7=1;jD3j4&)Tl0I{MbmBxPa&c zg3~~A%`Bqb@{GFgw{@UPB``#xcH2#|gLJ6krLrlrYbb0@9jg$vH!E^&@f+|pbdCc8UPKGH`k6W zxHiE%NXRtD8&*m@nnBGV0ZGpcA7>MklLb^ioaKBJx9@p&C@LnG20h$-vunIE6VVy< ztw@REFYmy=lwMdWvs_9Ec~LiF)32cbMRQH&iRn4MISNHtOLsKn$pSo|H(>!dZW{8Q8XS;~q z-=>pvOl0rqdRmd{ANSz;vw}7J4SOl3Thu%^@s_tXR3Y{8*?BMtz6}ioi}37_@G^tym$*{JN&*}n|b#}^eGbE@?ju7@wtY=Dk&d5uKBEd ztys{N)u~mf85%s6z#LUAUkx-VbgE#W=Hinx*7*dq+r1TnGvHgssCi67NGxxu*=WE# zDrzfFd$L$=z*?~Z4Co)&>kR2$HeBB#CJyIRzS7${$uH4qxuXw@r&05-%XH-e(U$}2 zi7%Y02eQYDq3c$m3`u#@L2h*?(pmJfK^}Y^&vbW->q)W4b7Doy{fAvYEDHLJ_~`8f zSL(s$`j56E+dvn&$+rz=nL3b_;33m~@fE4-kd>NjqnT9Gcwlx6ClHWsiw=5J_w?DM6LfL}1>L2xTsuc72s{ydpKWs-l= zI(Va@qazI$3%5Wv*aK<-P03EL2Fft)u}T#aaFY~}sokL6-U`9~slV5W5O==9^f9(k zFM2zH+gTa&zF%e{*ZK$i`6}{Z*qQac_d=crX6IiwAJUgd)W*9<=l7L=xb>71e@kO{ zM{!q?6)pbj{?n{5o`)Maa!{%x326$A-YfKB+Ppb@27eQE!I#KE(S3}h@|r2Ga!iN8 zu0*!FipZNSn_0Ky!zf}`m+JEgP>m}hq?&4=5%t}SI#**r8GS-l!$4c;HG<;$Sk-9t zK=2Id<=1ppY5qBOK{?T)BeIK4ja=g4V|&?w8!L^X%hvei&ez}!gYvdSX7T<`F3f|; ze8EYFU)p%LRv`~^IA-!?k>&}(nRTZzMH!MTQEpp0F(~?PREyv&N?jQX7;sVP@ji!o z&_$qrew`>J_Gy{=9wnnAuKbgA2WPOQU;3>4qLokm1sK)t3rTab5-#wX)oxFg#>RUy z2P-*P8`I@5F%^ARjbRk=BdDgiQ0X(IBvng|xz4T56YZE_ROC8HI(UeL9J0D_eg4M_ zGAMhpIYM}lImB=jv(<=wu#u0lbvdGb)J)_Pp=5zW3|&!qYkH`!*m;x-fdl;)byx33 z-SKsxRyOCMh|LL=nj+saR*gZ?QGcrXlR#o)l~DY$Mo~m^iButR(wXkBTLg7;!`CkQ zWOz80uj8glbbNJCXUYM(j0#KoLI?uWkjYfnCOVT2rG*#*zM|6h#5ot16$vkfY-WQJ zqfGW}h6)3EHGz*Na*?jahfIS^(iJ1wtNV~5?ChHAc^j{8;W8xwLtdw%F)|VcwQoeW zuNQ!7Pn%nv?8cS7R*77!JG7QH`7XS{O9(Cyl|k%78p_Fh31_!#LFDWm_Qof18G0QH zIkD8zn&Z(MP_2t_cfV2n@f-MRsHQB+E^0%(%akC02ndN8k5R45S=RG7oaJ8`S@~d} z-1oCxO&XSTr|2@2<6ty+$XwV9(aBV9kQ0-2ZYXjk#B=;UTC>QOF;YnrWg~bfWdBIi z1qGs;U2|-&IxsBaBD6|lE~NX*al5|JVt0pUS-NOd)+X~cTDLkUqH+ir{zy$6J4fnB z!dWu=LR+kbc={64ol=pbAJ`8ho$=GZn|re%h$?fA?H|)?xkT`{Ch(>VS-l2!Unkmx zd=a@pN_=)7WmN6Z^G*BId9mkrV`^1IdE?tM66xjD@$ zD1p0D}@jD%6G;tz#C z_p^C*UG)y>@O=p}nk4v^sPvd@DJ|w!*;0vX$*UQdq-K>}>6aI=Tf$)RXm{+PmA`z7 zL7yc~l2I{x2`HGf%4x1>F)4R0;oIjzOpNM9Upx>N%&sxyH2b+<9yHVd{Q>~3kIYML zGaS6=4NBTZ0`=g04kbkNTBaq6XlKUQMZ1l)Uz3rnk*WzIsV7dZqXtYXT?bjFmp*k& z8%&h+s_40hfhw}X3B6wV)}bz#tjndR8>SI7gMy&qz?14=C-smR=!Hqr>VZ{&iwqX5gB&kSlro9NI*x zW`AphwnO2I7!(fn#7CoV@?zC`#U$vIgjD}bu@Ruuxe`If$@!CJ48|{%sQ!xOZx_6E z&7|u7mY{-_)zXgm=Xu8wWD)$RcciYc%qFl($eQvb9?(*d5g?SvfsDf6=-p8$65b0e7$Zqt zXd(M809qJ8=mnthZHPz!dhOrlD}B+s?7t*=S$&%4hqAeH#f&{y%h?m+v)~YeqFX6L zgg4#KU+a39RGw8#-!rUOGf+Ht`3Ex_UsxC)TFqQugP>TPO+mA9D-}z%~Ct`i98o2 z**;u5;&Ea7z&18Jsv`iWed|~?{p+X(ser4I(dBPG(;gHywjd=W#Z3hV@G2B_Q(;Wp zmKU`sA>LIgVH#{O>RZiflRUGzrV3Roh(?V@v}T@3lfmLzt}zw&`OPI>iw#?ednus0 zyhRJ{IQ@~%j6MBP#K#$3+1#@lW4@r~0K@!TWxrudgNZq%&c)_f-KvWtXfdm2KBSWG z9)C zSQehXiQ&fasc`18ZT+H*dR&H@%FJiyrrO?aj-9}`TIWl2dMb`H+5g7dTLxCLGg*RW zW@ct)W@fx*C^Ngv%IHtn8%xo4i4L1|O4oX<1E9^LXDGau~AX zb3L2BpR>yfYD(^`jS9aDp9rwGBe$J`Ef%#4qS?S$KJ2)4lp#DkORU?G;m~1NFO+To zRIwx;|4wI8BLcMok2Iz`%|6qYzi$8L0T`OuLR6#e?mZc1*rl=9u^oBP zWeCL-ee_d56r1kI3&x{$?%0Au-^b#sQbFo3R66VyW{fX^H|dbXP6PX5r?#TJywy-m z+-2aQ6$^#o{<5Zq+meH?aVj^1?H!t-Hri8*Nk1)BmC12emd72+`7ynmQoB_Y=^BJ9o;PDPEkAD zVUjd7zc7AIn5)=P%so07I*03C6lIGcx)^l$a~nBGD92O2dIt`_Q^L0!2brNX#v^m3(m|BxLUYcMzN!pKbM3Y^2{ z@6Q!rE~EY2d<&aAUMme9m7<+^zx#d?URdm6cN`^jdiz0NZqJz&mO3Y+Ka*+TpHFgK z3?Z`D@qah9-`cqk`-7;GgpP_mY^|lTa5|x@;^V?622_7oIZe|y;%M52<9~BlFpy$p zfSLdCy_Ut-k~I40o^OOa8IWE9E+~+y$pq)dBLTdIdC->}TtsWXEPa{T!AyVdVk<47 zZdr^!{F1V}F_*-ZctQmvD_}>{@hq4r|D+z)r1R1tLY5xat>k-eh)yAnbL z-oY!`=$ljaOMXCa8QN4uwKC8!h9E{UjcD|{;EravRNW~(oL3zVF+DL|ztW7gsD5Ah zTUfU$6fX={N0rOGy8XdWG_5Dp#4~4$NB^sTP%DntbXH&tz~W=Iw1+7@?6E5}w4=j* z?dl(H+nbMAw=1W*3>X$vbXnssph14z4Cuh#=sFMdUjZ%_;#pYm)4sE|9ZW-Ff0FV6 zc@^2e{D&NC=7QG$Q_gu#9Lh0|`YMkwPCZ03Y?Dm-dXo+?74y#7n8z4vW`5KYn_-x{ ziC!#se@uL1_>r{RiPr2`cjloyI*fGg)8?ZuIOuT`WIi)tnIwO0rWLJNf0l7)IDLiY)DOgnyQ2iWvx)WK|jh4_wUlO*^)!pCPSfPiz@y zexhHB-Sv-0)RXp*K1J^~($mDN_=%oPe6v5St-Z!RAJf@F^Q#0>)|w^!Hef48sD{k%F@9>D$+TyzZ|Rbua-;;r^vF1HVl41>2gi(G3_FfqRp(v= z?@Up7fY?K=U3NP@R?m_whXCYZvBgWs3_syPy1n2HRUUr$;cQ?`JNCoE*|0>Xlle%uPB#IvS zDY?ySAo?7Rer|=v{)Xlr{mJv3bnw+xfp-x+LaIB$cxr2P$9|C+fXA zZb9>@BTU1eIt3AQL3QZoxTca%@OAaI$0t3!;9puig@&$n!0CYLh00mBczN)O%bz!{7mUD;6HMdo2giscg7Sj%FhuPfo&&io{elD>4 zy$8_g!wXqi0;AaYXJa|p?mPS9%P3nVM1t$+DVd+khmVW57BDI1d)Cmo;Fpi-Su-NK z%X7Bqf_V>b)VEL-jpWJjmFY+(U5twJObg>Oy>Oe;({_9``Q6(w*H<0|ppD#_j!BcY z!5;C0=q)R!+-nfMwXp)H+r5In-i&U^1Q+uVA$$I2>Hz1B(@lXL3=2}{ob}$Vw~B>Q zrRdp6`R-gh8DM=dUUD_u=64xR38pUDuNPRHM_cd`JV1Lr;rK|G7|wc)T(5hyBQ<*m$+i7r7R`fhN^TUB9v! z%k@tRr-3tgbH*MvxHpov+}Tl4&d<&Kr=GHovpKaeP0eY-p+sB}%t7{I)x%@VJ4}^0 zw_oS0y3OB1Rr1R#*7SY}PVfc%&T(Xgf)_<8QV%03E67`^yiG=chP_Kf`a*DEqfMn1 zCF(j$;DE0WY`T#!rkgVm;F?r05ao+WvMNQU1>7Yd`|wT1uHui#1qQFSqVkk!g%tj^ zHq)2IoD6i50W523vR9oxwWb1?LT8_R)`6%=1wLxeG3){cGq8=13qLMe4Cx8(C;ibe zFC;<*zthPZq#Q^fvdGspq=wEkUnZ|5-lueDIBbBQiJTS|RurKLMKnz>grJrd^4)c8p~u68L{kW1J|#fA{jFkStffuN{}Avgv0~i&QNq4-_-5>(wyLl*tMS!Ag%D+w-CW#AfcdnA}Sz(A%WB=82@md zZrQ&--<>Qv^f?N2=l^;S!vT4udw+d<*z88>y?XVAdVywLi}-kc+wCBKyxAq53*Cz$ znR5wLaTvI;40?ZCN4QiB!{jS9bcvhTu*08x&iNam6Q zRpKdICrJP>Zr~`#vLe7iu!3-CF#~8ZL0FhOZIZc55#Y(cJqRC)M+DMCMJjl!zqAr%=iDj z5G{=3ZhwR5k8qVq(0>#AnWDmg4K5}K3Ue14elt&vLIi^;h6okvE!O*Vj1Gew3ReL2 z`FFv#?;ULDLA}_U3*)<(iy+Z|WX~Ig!yMmv7XfnH@>sQ@(7`~5dN+iJq`?;iJN~~& ze0iK6jOF4Y!Wc~lDIog0eK8?E>+yF}(ZPJy@9(AspdkF+74Rv)l&>6MFttU1(A*X< zn6c3P!F-@`pkk6cqIKVuK1Yzsw5JLK5Pge;1i+DJ(0~1c-3lJ?*|(UX*vGZqzYIQy z0RW@`>{I!$zpuoAD0HDVev2QkpdMQR(;OrK6hq+QGRUX9vF#1k7ZrsLl+fpTQlN7^IPOFK>3h8(8)e_h)+QFR~Zx zRIJadl5CpC;+bF-&{kJ;$b5kAr{MIjgVRN|!I;=#3 z|D_ek-->|#rPbdzBEW-ORuGU*h)_5X5NOZ>FpwTmkY^OaDj4%jwsX#pDujf8me!#iOz-_HM9$ zy!!v+%dH66B5GJ?5Rkx@pwC(nE1>FNkWNx%sPsFY{T9LuACP54r_Hu$*ozo_pE{02 zla(xs!!F$Iszd>sCk%86Qi0|>SZRTG<2jg7bcU1>HOQicUzX%a2o=N?~j zaV88Yo^N(Lf;B+T|mlk z4A>U~SlnCTNh~?YEi00_h~qy^;uyIvgNS0eeBZ9_0Vh}J<4grysY2A8AFFBjaxGI0 zpuLD7pSiUk_g52tZNIi>7|Iu5mFbD5VX2qNO-pT!>X-TP>Qm@}( z08N4GNxU4_Y7Sq9uy6Riw8j(Q`e{UATjvcf;xIx6MK=kF-%noMvQ<*| zqW1uZ?G?zo8U;#ZIoPQtMYf&#?X-e}RP22SAUsl3`Zwc|;D}mt)wFY(Ndqgm0Tq1i zWfpwQ13dMdp}M-=9E23Pf<+h83c`4^_pBDICyaU#8@vOqfPx6l91vzf6 zfGUOW01%}9MPJ!k4o?2iVU7}=8I2t;2w?&C;{4TbccaZ*@dWQ2N+f-|$^&R_7{UP+ zapj38R^{sVe8aobNp7=J1q-g}2lpjiTA^8Se2T?y4JPVG6+Wbb?g)SNI!@;}cYb@& zj7>OO-l~fN6}!6Wrl*aNcgoCi(A=YXHG}GjaO?)gEij31Zr$b<$p-!Sax!i;s$CU` zj5mubra1V7Zk%J(wxq}1U0I)oCp)GZBn<@d%nuH*xMD?o9{jkL7vXeLv|)9W8c+?sHGL_mIsJiTQ_-Ed9@VY^%=J5ufODI(w#_%_`Yey@z9o;kB=n#X z6r}bK_A!shSh{B55VcxEB}O)J^qG^OlSrxbiUhD^Iky7YaCs5%+)4RBt{0|DNDJtY zfZH4rFrWCk-SIdaoDP_$o%oFMKvbkjn^Ir+~a+BSj)X1}3j3N&tUnO);eP zT|p(~DfX`kFp&b9`oDRx+;bLSb-7d&CjWuls?yH zJ04I#lCLr-m@j}=MZS@M6jZdOKXwa!?)=5$gJOtkbE4yIQyMJwm-w`-_r};pPJuL! zs$lg7Y1*-~{Wul$RqdH)bxc+cYDgA0Ia`a}4hGn^5MS(QMPZMFbsH^L37~E=GtAvDxTY7}0!AL&_9-L(LMTvn{7zLxqJ&%qVrL0e!oVwk=quj$RGc4xi3(fpy(@==3ac+bFK{C2(Bk-{1iH*@2coU;Ug5}+9$$v4)!(E~Qh&IpWQOq5*!R!Qm z%S%J0d@z^@*WeZQLp7~J?qOx%_(GQLC1Wjk*!l%nyg14%XD%;T+bhGHpOuZr1=sZ5 zLO>pf%(k}-o2%YY;EHbQBB|>|Wey7RqGQ!%BOPFOIGJNw^#GqrV`RJv@V(#jxX-cv zdUmuzH#djloli4&K&$DhDrA6nGkd{CEYPn_9Eh&%>8!t8Us}01Lx5WL5+>*0V8VUR z9k;CX-L>6Aj-MkzQA}g<0PD`Cf{QT^-~*77t`E-p@- zTA_%IW?B}#+|0^U z=KV*m^g?}>TE#2X0!Ab`b*kgA9t^ugCKwMJ7jky9R1V4pD((OV_wa6|IYdQjvZ-Ww z!e3aD=^^<_L2|+x*3}jDo z-_*}9x?&ZfVN!i~f8t*(rTH|-PYj%(16aE<4yaL}^TKmyNH75qsmUX-==I5U{RGRx- zc;&B!=k=fj0wR>?D$DY@D`*D)U*FUGy#xAu_F?w}5(gyl(g*Heg`9By#Z2=bAt!$^ z+58Qq`X{*RlYZqdJk);;xa!}jR{p2ps=xF6dzJq8@j?G96fS?O_@9D+SXtP3{uw7U zr>W?$#)b0pL~AUOfh?<#LXPhitrba^L^1p8G?*Lm38n|5NLq6tfcrzpL1uU&-GwIj zd;f2GCe9qMoBi=AY-a!A!`WYz_Q#Pk|>Pa}@ z>+vIJE?SA3g_XyaBq;X7F!7(gB|hby#A3{yWyO~^eCVfx^9Tw?XN`F;DO!Q-_Fu#D zLbw9OoxsBA&3yj!_uFSoPTg5^k7Gl=0QuTln6C7V>Dmp&TazPQYV}zwQvi7kLkgxB z%Iizute^mK-ghjz*>!%Q6wp;pz4-x(>JCZn$rwoQRwtstsl zk;+;emBm&P^2GY|#2Qzj@MD-El}g;(PSe4#8zqht$`Jz?+>ysw36KtY=aIv5p|!w|W9QUQPBr*pQfJe&D6>xyCX2lc<%t5gZAZ- z=7Yj?hQ-HS1>SmOVavIsO4X=j-gvw@edX_R8?QU($A5Qy_t1yJ!J{4VimI3uV;ksB(eTu^gD z#}>rx?2U}+z&$(@2L0&KA*Gw@xG_Wd-#FWxy58E#;#fbVkXNU2jJJGU19YuqvUyU2 zXyaxAJRFt^_XjO65Sv90{GK-+)wCCQdajp!ZjT&4@D01LtXs7MKhSO2cgf6V#+f-3BjYwQ0`%EiXZ!o=}O{l&`m7ZDf- z3-@2#TwI?((*I{fV4VMetN!m#>i-J#`A;q`&VRs8|3zrze{gYqR{Nh5`Pe_uoIR+< zMvlsPu66oysiu;J@-X_Wu`T*f z23O5xW{Jg<<3s$GI5yKY5bi#roV~L5$2s?bI{RHjkpJ0(Vk=D{2hIxX>%n!cM|5M% zNHK7{uraaP#x~7CWIXs7?28=f%SmO8UgyVUL;229=Mndt@_H*L@kUlY(wWy{=9htU zGk<{x#<~_aJ9_{$*H|IhP{uU!XvgLS+H7`5MO+o9q=AI2xwEdeCROa8&YJP^ju*4= z4n8hQ*#yi~ogY+}ul(MkleYN%<+Nz>XvvN3;vC6?#hGjkQwY-_@Y$@H81Rc80a|W) zs@zu*^+zGRno~|y$DvS;=jmsD>{aax9D_SGU%rto8nEXo7bq4A97-h0;?2v&b(e(E z)|1iE;aE*#xKQTqPN=jx>$A@A?Kc$~{xHjfVp$MvyO#*-R5=N#sRlAYXn{}33dCy+*;lySbms~}6lV6qHh zZ8URWCmdTsWSmV?4~ve0nORPvlUrN9WFar56-+WUq2@{yz)d_Mk;Vlkq0zuP4ENe8 z@L%{)igwF}74gQu{n)0Q)r2TSJl#DY;xj$sIIAuL#U zbW$G+ar@?EWFbUznYo$JzT61rw{cyLA#cSHi_JGl3d)}_2AHRHt24uBdb`;6mWHd} zvQiX0dEBQcIbgjh8*va6&}u|L^U^ZQKnE9GK8aRZO`7;v1}#FqGpf}K?%_48-4}V$ za`_M^EnUR8^iVJ}7p5Lh?j9?+jo~>1{>0wIItUu{nJjon{^m2up=H-~2AK^VKOZzK1 z(NT($Z+fFI+QgV^i)l!(1`*4PBrPD&)2EA@7gi+^tkofGD~Z35QE=xq+sTZpw;$h$ zrhp&y6=GEBh%T?bWGjmUv^Z)gOyFX1$jr7FA+Lg4Vpc;S(5ee1`H@^wb08kqzD=Oh zXv}Y6!-)sX_w8@35jHJ@bU^6i`#kKYo(nj);3<>?Lu96;o#rDxex`YqyZ`=4%y{F z*8cFJ0pQu&o!wzc;N+ctEmRloYpDp8g)jr;u;b??ZcqpDm8bZb@r~T~3Y4gH8dHWT zkD8l~_XV358$-OwJR`GYUcdQG8IyK2eQzAQoI58GiqT|O9@*NS=Po}&o=>-OzAc#P zIAt#i@K>I`kGJV1aYaE|)m@R@-28a4nE?M4!va4r+@>?}RTCopkM=h(wDeQwZ(pc9 zhw*!;W!-qaj~gUP!;Cn7d<8}3G#!$})2s>ExpIV~cRr(4P%&AhfzT>y`@W^$b2-tv zRCVoZ@pFz?kH?FqcYzx~(E17jLIV-Jg09LRRaS|0lx#RsKy2$uSHr_`R)Je)iSDY& zmiO)+o>vf*9{SitCSKb-{^Mu}uUEbN`3NI-55uruKys7pSb6npLb0mj3{ZcDhQ}Ji z!~{Rm0A35c3d#B4)r7jKRFL~b2htTQ#f9mBV;{gusv+X*viKY)b zd10p)bj0|-`BwFy7bd~2A1faDlIw{_l@72+uJ_mCv$FPSp0XH8zmQveHDo`RPF&rR zACamWj*OAS47wz@K3I~GoyuzX99s&)L$!!VQfGBvr;GMh2q=OyxpdapoD)q|i`;P5 z$XcR(z{26Q0PFP;`zMcO$!Qx^ExiZEQ^C8ZbiPYHHg;$*n=Pk*TLV>Eno^gkY3#Tc#$3NN| z(0-S9LDoO2%mvK-;-B!?@ub=;&f`=_z&4CXf`?R4DRogGbVZ9SfvoF1$AWaK6Bxb7 z`^ru5lCl(%|ARYUh$T}vvxS%=*$@xy%Jv);$8wPf#!xrbi+jeMsj;H4^EoOv`Kv^bpf@-3u1Rs!ajE zOu3o1h#y~9_CMh^bo<6rr+J?@6|)er&&Qn`N)y33QKl%?7CPohi|{KPBi$?1<}NHF zBrlu}UY=vu-1+Q|=nTLZEnwj@abe-wmu}r}UfQRJ5|J0-d95*M-gi`W2mD#tA zsf_2lQVP@remSE16%tHSjeP(ta>UEsx% zp{5LZhkOx^F`7ndHRW3#V{QbKgK)UDApSw3J+emXT$#q8ifgCgI(hSxhAzA~eu_O#qEb_hbsnzf=Fx(`(OL z+b0axA6|;GLDvnedVp0T%J-LNLUs$}DgICDmqwD=S z7OQr$Oyg!%!d1#kFO{ue-_HW}b3++Nitb&|aufGN`1g@Fq?Ym#L;F;$>f$MH@R;D4 zzu*PmJC4wo@LOW+S*K&@wu#IgJGA3Y+qVRTEuM3*8mZ!Oo7E;4nRhF-eV()-Cz$<- zDmV9VT4E~S8GElwZMLx<6T4m}Yi!NPmnvD=weP-XbiNiU(6tz|I+L66>ajQM#9 zYk$sBo<(IX43^jGY$BvGW`<-Vj4n{4*N~V+?(A(5IRn9va&(1Mi-c!3jVRl}pd1d+bh4ZuE`7t<^776;F*H+jAYER^;s?U4jq*Z?ht~D%5V7n+s@k0S&BgH zzE<-;F=&|{A#wd#&1Y9bn_%;8KW}XoI6L&XPks(BTrwr zUV|p6)>%A%78~3r;5Xcq;2y$r;d!r=4`FdW($V$Qd9p?xOE=cJ8&2o;34cg8)R>&p zQoa!R)@>|d&U*+_sZ)J>;vcY8>D*fQGX{)SHvauyuY<5$OJ-1TRO$Mhe^Yel8I-K; ztIiBc`{tLDOn=Js41Ahl-jy&j1>pTD6sIA4oH1%uKy%Kc zK+rYSy^6|{w``dH6{wj$vicOUw;u56J|%rl>RTW z?*HaZ`cJI;e_$T}_bu)JCHLt+V2l4_tDA$3=f88G=KRHgJ%suf19nToFFC3XF9QaOpoXF_g}l#SAav*WKlO8j5OJxcIOLo)m`9YUwUY8YlhC0rBI_ z-A~qTHzrLZ3U-zp1Y1#O4qY0)-xOvA+t+Ynhk_GPJ~_;k88Q%(-|7Z z_AL@uOBm(wcGCu%c7C)Wyu{}pdtYt0bZ4?fjoCNYZ!Eq|yxy;LUT~H9+52Cd6g}R-0$EH?hU?^@1_GuDTg7wPC@NT(`JY$ycWNJ=53#qzt%PK<$e9FFtpQ^;cj3iL`v z@tJ1K2{JnHntM}xg%O*L6_kzdOAu}9&bm50eU!s#tUi3a_9}7RpM9kt>>ZP)&4IZ` zwx>Pq=G!LHdMMIU(%ptS=XK@x^IptuRzf!C1`q zoRHi#?i=>7>z!rHvLdWxU)-GgMtG1ni22ywjfMc1%5ZwSqD=+Wqa96lu6LHF(Jhhz z=&{6z@K=;SJ%Za_6*#V^ND{7%R`Kf`q@o)*P)kbIo@~TM#`$7szfyK(r!ilFJ^GJ- zxz+KGN(-gW##GDSb0L_6MHdD|YkGoq=re02KM>?B{Dv z9Pciu18LacI}}bMiR!ZU%hVe-LHwKb>buPk9O$oG{7G#SqIn9Jeu8spJ}6r{XJKn) z3YcI><0(I2VUaZu(Y@WKQqc^LAtS$7AVx%vX8+>&X>E&y7ggTH=g;|o0do6CE1!FQ zgPNlMo`Dqou6tJJ;TQm4He)BA0d<*8-rckwKClz-ItwMpfBy&6y(&vsg5laAsHs_a zN{oA6<*3?5j;G2x&Cv`xyB{xcmj}sX1npX0ls@#0aK4PsM_c{`J~@TcgoX+7{{Y{K&%eUrti9V zIqXYh_)qaX2g^dw}bEPx1$X-_GPddq)K#}!dx*arghQ}-~~ciu98p{29A%qawG*k6!iooeqnY zifVW(?iZRV&3-wgRng=1JU3Tp<@1sBjTzaWYu;kVsp7%x$jTPJIT@v}Cm4+EEntK5 zBzFT1#&n8#Nw{kCv5qx5QhXqGMfML}0)8OXcy$lIYmby7oeq-2L*CmS6OmTYOuZiG zT8gN^Q7YoVVGJkVaxZ~cF&3@L^K z>J92+=dA?6-l6p=LH1>5BxT$LCfP^SDii;^N+yiSSwEh0k(%08D} z%73>Hibd*a!5ymL3di6N2NFG6^VB0{6SqkmiNbZ)y8-^H1;a>FSMHhZ#HTZm>P2OX z4R&C@0JTJf-s~b(P019d1+ndR2C&NGS!KZrlhfRdKQ$spysx>->@0tgdZ1eqd5mDa zHpg2XPDzZIXa(rm{3ydaJrY==bRMCk%<~EFkjl5hs-`ESWJg7jLaXMQrYp;tN_>c? z05mF~CkgGCNI#)e`Woe#ZsG9gkBE4NvKbu~5220hnGINsh;U(xt4%dOYF17m;^=*Vi0P*e#h^MlG{xF(N=GQDVJ{iD{yjJrK0B)Aky1i?F(LUno!9K zzzGii4I0uY#3*|}aixI^&iMx)Uf*SoZI8H2s_TBKZ5R!7yq|D7GRc5pPm+k>So913 zwU`-~a~8d27AK~T>W=*gksp8Ws`N->Y#-Ag!Ms^yhIU%7cZ9fwAK!81Sbf%hF)uuw zB{L#l8U@qzxNM1t`izy&)}k!OMHQ5eNcXiu3yP+LSi1s2nAU-YTtXo5J4b;G@aq9Z8d=o=#{h*L**Hf9A z4!-6wmD@ybm#%Huaa>3T2>mYlvl;9fJwV43GOf5_#2xU(aLZV5^OyEQlY(Hc($j9C zX6sFR*UFDAOjjQthenA5OqTfyFi~U|6U49JslV2{xD5A}<*#x130bfJM3+O@Vl;6> zn^RW~5|IrIs7E?cw+zJ`VLuj>3j9Hp_#4gC=sNanZZh$OC?YK#M7N#Y$%d#odQ56n zcySSdcdvx61yFxP^{TNf?L$l7^w02}F4jVH_pJlKVujKDyxyMgD!&nFqpk3A3H*UX zq>*~tTdJyDjbdO{e||q|YYPpSWqsQFb@`nF6x5u`WTw1U;S%`U?;9Kb{CnTGZu$lu z*egJLnC}76l_=VyNLm}WE}mIMh#7OdVcN)m9)$(xoj}=U6p1f6$`B2xB+arZp&aL> z3vs=~ZOX@VK!uAnQb!X+NI5pB>Q>AaufjUor(ljQz>E_RYTjc~E7?>@@gGIBXQx zrqILIexWZ_(ZImN()=I4)D*+#prXj@DA`?X+Tn}uSMtSCI2FhJ%poF7(q*Rj7r3jq za2ffTIIX&#?3V^Z1@AP{emX#M25(Y zhRQ$!@3;&0IG_ZfH{-E!kK8)>cu<=Fs6)!7N7~zw!estQ^M*;3Ms#xJ$@fm!p)%5g z)#x~|p7d)R&U%ER(^6k!DwVYjhJMPrvF>B$nBCvXOI_6kwL@B*yIsXEpSZK1G7a>W zN$?tMbM)$&e=L8pXN}u$emGni) zDo9LF*NWyXPBW}?2s-hN!e7FzTjY1sPLge%-N(et(G_H`?4b-vRcf zp^`^sj~7#bKq4`o1OQ2X*~ZQHGP|>lG%(aD+_DC&Eg7 zFu??#V(pHU5AuDdeX){R{#v;J@1D9VXP478#i)=3-DmZ%1Bam@7j|GEX~xde`W&RM zd(~kyhI1p9Q+p+Ym#UC-xk2={G!L{X{kn&G zgm-}ztdqAU>Lgjqy`?kPaBX`9yr4cv_SwpQe6p~%5b9KeGLrvS)PqpvY~rRna`0Bbxh6seWHtsfAmuMEMHLQ&7l5>FSMc*J~`klKQxK$EU zwenoJ=5c=58F5#T9@S9*-DM){e6#Lc3NKQFHyJ*56RctpzfT>F)jW^IPOoy4TVwDD zco_0ad?}P!Kxao78jPIu3e4abm;Cig^F{m1`iR#gKk0H?r<;H3bh^aS{7y8w@3#D* z7l`$7*TTRyF7CL42{atAJ*(2;2sy z?CxNAD?55}s`!Q2YQ{gCiueG-Y9?ZDE@0j$2lDO%|0hEMFPm}-1&`3}?eG+?pwCz( zbX#tt^`2|e8SElh@GipDviO%04oY^aa^6hC+$CWhJOJG~xAzh|su3MT1`KHM$q;W+ zacXL}T*xp^X;_)4_t_Y3bvMm$Ye{h!#MO@9PaIeUIE>6p$Q$%fcRp6sxXxLn(2I@7D%Ye`FP5)n#K{d@rEd z$h(7*tz%ef=UzoqiX0 z{CRc}Caz%8$@^uQZ3LY3+g72Nz|Ji-lrzrnT$A|`q2TM$9oztx8{0*tGJLNbMYfT+ z1rHm)@?f|l!2|UGjommXT_oF;Xm7Hy(8%hR!&8Z_KE?y(-K!%QxTCUQIQW-5KOwa{ zYNz$<(i&R~!?Wc6F;}oHi@`whhv(#dIGhndgx8v$e9Ow$K|)F4CY2+-bYk&>YOTub z4>%T(Hx;*{f8`9~`oG4~{d?HQe2fGe{d??-+BIjjivir#s4&xj^mT| z{GTBhq5sVpB+d4t)$E3d1lcscfj=l0#}*R*(-#y`Ofi5~9yu3tAbsznURIIS?&V?J zBd$8$1<2)ds{j)FzY=8Lc|N#%J@h(fW)3lEd6=tMP!$LGqGGEWp(k5yA(eQ=p21{iF#GF{rN$A3DAXPrvt z@0*YI7*5E!&1c*2Bkd1=DenAH5|XjA#O2(p0FEqho^4|@E`fgi)lNYu+KStxADELq zVRjTkj467I=&$fWY+b*UeF!LrrdFIs*O{^Zvt33^B!uG!!awxWja%vLlT>+9{{C#Y z>~=4@J2Ip%WU;@zJr4D$Xx@;z2-!o zlh}qUl%lgoI7gy*hW{mNm$h`gBx%;u?OJUZpA*DohjEX3%~Q z_kXc@9Scc^eTA(SP1fNfHl+fwQPV{O{$hbrTC5H4t;wRC07=IB@KO24glR*t_5@z8-fv+e#77 z!~mTgLUXY@Mzl2f%~K3<;bGHgr?1jIxaCdL{wo8M^CVz5EXShMTrJ~px$Hw1(TrEz zAy3ziRTO2^a9FvOq$RP%(eyINVA(JQ%FFxu0};PI+t(<|-gs{ptxh`~F|~s^x8M@d zPIbzK-U6g+FJ^(>r8iGtvxX9xYtt{r9@xJ2F{>BD07t0goXtJcZ58Rp~)wayrvt`2?O~*B? z#}IidDtj-=CP+{Cj2yK`WwrKEs}I?4xbCplT%ShXHel5T4Eh^gQ_~|KqKp512^zIP zQ?P3xiAzd!;zDsXM-N6&3Y2E4$7%doq(k4OcPqU=V{YP{+&tc7*+y0{DYR@&r8N&k z-xHVZ_8vx)8Fk|&COnpbL&@h-b6TSx=K3`d>TDMUp2$hU^Qit1Ka_VR5G z+W}SFe2a|SqDQ1|S-UAhUUB_p7X1?YnLcIBuaH6}mgJ>h4YaXE69~^F~LU^^~$?v(ylt zQrh^3dEW#e5ts>aX~R>Se}lM5vKkxl@gc6~Zqvrwuc{(-yw0|rktMPDHez$iYB@X( zE6$^&5m8LOL7+9tm4-&eOlx@B8kZqCLzw+ijyo$(Q7F%6Hyyz+B6Lwf3H^i6oM#yQ z2BxhdBMkrBrBj<4!mfB3;Yu`Wzu2N3JULT7oOf^iQddf%MCc7vn!e`tS3CMx9-$Ni zi8NS|dYWp}wzC-#hOt@g4xNWn2_Br`+Ym@pr$?y`UNgmXxI8B)b+$G+Oz&W`gO!dD zQkbqD>K70p_lvsva?i_`W5XJsm^>w6mo+X zGTv|Gn3Wly^W%lrpg)TCt|guazL-a@0fc?9^OA)}&rV=tJ9Dd1b|feQ)-=hvQ9Qz? zj)QF9CU}WX+A$a7caCXvyk5dXCdTdL3mA#q0=eA>oqpq~Fht=$TJ?OyZe*^3chm^u zhxYs#Lk>XS84`b~o(W+5?xC=IAJ8w+5ZE{}LrA*QW*e7fsB(}IUY%ceCtWogm!M6k zAz*?(L#R{1Ck*H)u1kJgkUO_*KGe>(?|A?GV$Ulu)`)snSOi_rx})oWoa55NL%?nn z+gG47jF?ihNMXY(nWP?o9xAJ3m;7cy>Q&LP^m7Ax8U^dyUVwvYdhu@bDS_Lf z_2EVpbP_Z3d}X`mqUH|j2#Qit&sqyKTD6i(sn?j?l=lXPC~n!2i+pP&=gZ@!j!o#V~*}r0k4lV^C79X z2DIL!a4cuimhE0o*sz_;#pymoy-N$B`pyQZCZ_&$?`ExB`X~)yP(+7W+|Kh5wq{*I*?NI{G;O z35j9SAGbF$aQGe=evw??B)T`<^$SWjPIO*#4h;D#N3=C4b1|Z9a(vBje%D;0rZ#DZ zRO-IxO>}G`L*r6?9uKHeI9eS;bgwKyM}tQB?D%t!@0I765BlbjMN88wFF*A?EE;MZ zcSgpn`_Tf$iP=!8ZNJ!3a4U9BWb+g{z1%J#O!AsvcLd=J0v! zqpHw(Y~HQCUn3M69 zTv<{v1(@X1OR=aVC1qb+w~*x#FI1^V}&glt= zjITRrS;4(!9g_;Z?#m8b8D<>5BwTsG@HyGUt?i;q~Lyo10duwOyvLTkj%ORj0Z;u5%)&i^23SWQM__#7UgUChBjr z9}^8o*^UA&4RD`E*3enO|B^$fiTN7?;=PF?QdG+w!fMdR04g$GY2tT{>le;DQD!BF z`K8OfgSTc=Cohh})=p%DmMp$M=l6eSC(>*qX6@-sn#3`|zzmmq#r4&jNNv$&3ET#+ zas`Z2ieg@O#oL#*i77M~Pym(eAGur@SVIA+%wBNPGG(Rdqe9WDi$f0JE`6d16A{Ix z$hEE6cjoc(V#v1oIB#h>k{{pplu~d!?2?Ig&V__2uA=UrXpQz=9hUW+wJ4Sb7B0JO z6a_>f;zCZe$Jnhad5qJ zJdOnA+K&K5zM<-6`lvJ(d`9|Wc?k9xIaJmX5z2|)6-$3ieT4eI1uJB{N($p~gy-fM z1p})QLnt-vycq7T#9;pc^Ed zGiN}n-=hS!k&b@esz*L!(t|(!`Tlq+7KGU@`snz_mcm@3d?ezDtqHwLMjcvoidebU9b(kV+$XY%{kiBQBbyM3-P93q>9}BI)89*)biZ#Y;%K^0OSTRk zJlywP@)dPYi?)$b&W#7hWGEj`uG*LP5ykx^vTryf%FPiA_LDq4o2gnPO7wy8!M&>e zIcl`HT^SY(2622iCLt-F@uS(JlW1Xn6#+swx2DODjcVUAS*ZZ|I2OMt{v;MX#sF>p zK8s5kV?`PZoT3I`|HUlUG?IUauICGq3IV&sKWI6=XdXO>($6Y~QAB~d~GSZBzKp>Y@HI&72J>98swp8(9=;m(|WYR!n^QwBSSID-<{V&gr zDLN0yjTuSHT&M4y0*ZQ!7s6v)HBpqtnIR4=SiE+mh}Q3cOVh1IH&ZdsN+W@3IxE(P z2lcT%FVskeN_JssJNkrN*=}BTJhNz5-b3gOga#qi_$L4VkQV&?as? zgbt@av01k*9U&13kDkqN97(PL0EK7}MFPSr0p16sXT{?0%kn#Et*z#w0c^!K3iWbi zI=|AsB-6F_`RF4N1SSFy zyyzbCv%Ox<>g&}VEz9t$-L%w3MI8G*pU@YU;c|TwjNcO4)i>WhVHM$i4(BqgGUUnk zEo7bE{+y@94fK;C3`PAQ09VB#D*3?R5XlyLuUcYvxUx9_UJEviky+DmuYP?8RvyxQ zV+mkxP!UR|lX=^4Sc>2LDotVhU91-K@mRFyJEbrc4UOnL?PXFP$hBB8u0T8+%pa#y zk|c-z5JesncdD~G&vK{3p_knRcYD7Od0$1MGl>pjn-METdKV6XE%QY-L9MBv(UAYb zS4XFRqTtIrV33%UqWXp%Ro~Pr7EIt%98%{?n1)kJcsY|nnjk$W$#975(_7O9e^E4Z zxf_12L@5~g*7|#*36K$HKv2D)d;iz?B*PE1m`1?lX=9(9;x|t;imWq|!&aq>3zpf+ zSL^7wAw|0{aE}UJJ9t?;`A+A1X-h7ru^iukyq?{1=f9MOaH^;(?F+@SJ6Rjnf7F}*ch=^gcm8kXm49(G z|NmJVCU%DZLbxpbl~)e`?v<^oJrP+{neWhfXc={nfV_-oP}%!S|J|B5Tf&V<7O^xv zWqTMdS5lF=U`zrCH6W(1BT_JSdoHg~DvkX9=*%U2q^IuDpy|=Ac0|fp{wjd1*b08a z^An#S4_8t;5{WM|ZPo&jP|v`Rka|D8s{Wr%Soj%Uhnl= zY?;L4`x#a?Fy~zZ`xN4`o;r;?3G3mo)p~5r=SjbfZL#<=(N16yI3DJuxk2fgZ>=1z zjT%#LEE7~3%9nUtpnfk3bG?65E76*Jri2|BI#Q5+iKlrB@r_S1BgpO&H_GaQ#Q04P zceW;=nMn@*{_;7jcj^;Jc;Z#CWz3L2-kM^&ygLrN9dso=u5yo6(pA6w!;R`kFK!Ti z*`XWx*H;@nAHAUQP|R z-!lKf_?B*wc&w}5B(Q+QNQ03XE{Zt3F<2Fa6&gw`Oo4NefJZKl&hIHrL*89D24B5E z%$ts<@e<2V!(EK;spVS#!}fE)4f_u}grXeY?rYe*_cw$dSA?J)#1lGKmpoF8C66RM3@+G@#t^o&;^Ayipj7G`aa?>C4@~rCvL=9Qj-wXFS*# z(pLRI_eN8Rlhr}dO59mimpkghd(Iz{_U%F%bZ}%owTBfKvl~q(Y|VGx7h_Z`LGWY+ z$Agn|?4iW2T5EU&VYxn<0vPug&nQYUEZcXgWg&JVqQ<31WyE{_1DIeBo=lmqrA$4~ z&2tk@kejL)WdpPEM1OD!mgOAqm$@)$gW*LC4F=vryQ}Ahwf@pm#9Ib>HsG4%9s4F6 z3{iL<^xW94d9eFqB%deVH*m1fh@3lcN=Pb?f_}?j8Volv1;jsfkFW4%7FUbIrxi>1&cikF-#%sqt*g((qSqN$Yxtpt&rnwFK` z7YV*L>q=zv5jGTWrP;d^RNwR$lhU(a4On^P_HI5ct95CUK5nk9L$9JQ1dmnn2sYBY ztJ2hsfY;uMF9&@O=s0D0B0tAu;{N?+l^AEsYF7{HgG?&gR&Oy4c?OQ<=3#&vi>|L< z25ND{A|z5f@A$Nf&oWW|O^&2R!Y9q!=C?G(>-4y11`$qME|(F8#s1Mzgqgr}nO$0u z7z0zmBV&CmRua)ULb66x{^H%wyD}H)KuqQGh{XA`;~T z<7QBk6c|hzclpUBr-2}@H|8iU|_pyd#vL%hi!k1*oMm<%^mjS^jQM}F2S?Y%; zw!dV$`rHZ2&(3l*2M%KFsO(+ab|6z0n8G6Zl^5j7ODRl+OA_4r40Rwwox;T;VXRUO zq>wrr;I_=lc$3SU*TGznMBbcx-Ijo-ig^@6en@^tRc6R(868+68zgtj(+IW<|3!l-7wxzdjE+LLdEblv@QV)RGQIhny?`8 z*ixc4Uqx&$)e&gv=EajqKjJ)CE^~~mee#6JjcG=^-Uw!Q7EUA!)Hy8kGjM4v1fi?C z`j)!0Sn!L4D zNL+oV&gPou(c`#NB6aYNMj&+T@KT!-YA3BjE3SHiC2{P_`=Pdyd{!}SQ|otzWP92} zBq@-wuqa`ja;JK=?kG)jth}ba9|c=HDq68k;u9JT-B5OmAaQ~`jAI-H%Dz?yu4?9F zA!9Zc5^1it^aP`F1$K;IrhxV*E5eb-JL(bz>q{-#aioTTBcY9Hr7-nGgQTQUJ{76 zS}~k@1L=M>KD3eWl2dyQRYsVN>L4yRS?DW^DR;6lS)yoVRPN-8vUC#Lw(hXmK8PhV zFIfv@F`VCas%6!lzfR&qOkBorS{DTpy8Ir_%9TNH2p#KZXBMi%3Y5{MAw_|Ja60M2 z#sgpfrjFcUD0^%aO_uy>pdlFy>#Ji2bEBk)srHXW+DP3|@K4@@A5ROgv&{_$`;tEt z2Fra)1-bav!eKFGZD*8-(YtzeiS#oY@n|y znJjXQgl2K0WpB~^H55J|OxIW&0OdqvEx0#1Dg+jx7*k*o;RzAtcA=|Ux{7lqG&1X| zG}kfuZ^wWnq6OgyWu1e{y;vob_ZxEx9GS!XBSG}>SVVS-qG zcEj9k*GfC&)AB`!;;U})kQ}(Ns#tsX9dR@{VHTVHd8*x^ zm^$7qg5!xa6r8UEN(qx}XZm3?m?Za874tr)tgf zir5wWg#Z-^fIyRR(}>>33}NuJ&q-`N0ZNaFQ4CGB*-qnemOd?yK`q)$i6~GsuN~V1 zrs$cC%fLDEIurEcI8c=AwiP!;_9cWpO8MG^c!j+8yOCCZr0t0o*mC(gy22YXm=&+RT%!sZ{l z1^TR`^|?UgkKqCx5rplJvBVQc*8Xw5txan*_y+ievq2_$8`jUHcOja%eM6XtbiuXX z7fd>wyeWc$<%z3uzBFJe*|S71-F-av>=pzN6v9b*usdEG>@kpub6_wn+!dhWC{1y~ zd2(WR;HsAlOJy>#-o-94T8=NWK@w5QoW4ewuW}Qy2Wp~9F_cuHFDNugvk4EH1+h>G zE4aih!hcX+U>8EgQ6e$&D5~mbMCh+Cq3}J@4UZaEeui)(!N7`M+9GTwO(fgDiKy}M#n zmNUY;ej<(uLpL&qiZn{h-GB~)^hatr=c&k96A$mnake-vNwlNTdIDtv^To3CU=!?jwluk3)acQb%9@E8PfV#Gt?J@$ z`gChiL4fJ;i!`-?cy&@qxxhO~>Zk?}|I7j*Ngj_HJ$eTT^#?)8)@OU?On1V1AFsBw z->~s9Lk>sG3Dz7NW9p$Q{sYVDch(0!&yHr9qxOW*HDsrfzE{+%9<~P;^*z1`jS3C3 z?5GTEnO48-yctk)2Gomdt&v!1&>tooj zth&LBvF`o7A(n4+fsRgVaY_`dGdWy}-cL(wGFdoTmoq346}$tp#1c~co=*d!&hQsK z*e0q;bZ1u*#<|~VTxz{tS<;4XK!K%vV(IScFbbtKHV=FdLb(9_(soAZ5HZ?BwhY&{ zeXVYF5Zp$;>AqT}#EA=s-Z~}VAReb~g*{jU)j4iL%3i91?{K?Hbenc}mnXvGrt}NC zT1E}5;gTw33#-z76ey|MTXER%gc%;K3h$s^ZxFUL-0!Pz$rP28RKybI08izC_rigc zd&Ty<#+8S3*o5nQZfV8|uI_C-F2PQC+WiG_O%#&n|8#`W^!Pg%cCB^W*>a^cpf9vB zExz0Fj-8brzV)M$k877fJdPu#t~iWmj|XpWFWKgZ+%;1oq~*I#^l5pE*(9)4G?+tk zoX(?UYTT1P{E&=|ijvA-_rp9Bc!DvVWi!S^c^phLrVmG5%R0Zi4C!=3f#X_6X1ND63OxlMHu|G2#$TyCiF zKCD?)gVGM!tI4hTZhbRg=e@?`>v;bD_Vr@7e(k)z3DUY|tC)x#Y0klJ68nOD%N4FlH5tHDbVp^KyC{YH)uu`s3)M(!RP0x7iCDruBN5yQTN~ zdvSa3+Z7#mJ6CRVTAo%A&NkHtK@wV*I0JkVx?^g>r_C~z;caHvbiGJ@Gs`z?>6P>R z`P$#*%C-ehHm>+KwOk#i^_bA`$_Io0##kZj@XmkNL<#%vR~uGH_v)hUAciQEz^4^W z6$k`N5KdsTYu32U&%IYuDAoceC|patYwaUz8YZ&1OOb_+VPokD#Z3+B|08T{>_-Gg$ITi>d=i z><+uV!&~rRG?pqOfoF=F<@ymaGSwlJq=&_r`$sUcxoU2u0fjChOcbhm+4oAmb9pLV-}O;9swa+wcypT8+>iRVaV$NO~1$pZjgU&!?u1^20zs?TAftT zW#v)r5VL}4vX1P@U_>sT-<fA%L4VTT3U0~H++5YiK0Dz&{5)ot}{VL zAuscC(jK__W!6ibSN7MiV$BmU+q0uXYu168vxYQ{#VwcRpJqseTId1~b;BY6_7;1I zu)Bz`+U5-b!|T<(TqoQtD93oIFMas}TUWX26<-@+fK;GYtHW*13W)|e*aL=of&?`< zpd(+zZ7yfOhd*CSO1IIeTI~eJ9E*ZwJXl1PxCCLjkz9Xw^SFx90}t-vD673Lsl<>R zePb!GrvV0(?>|Z18aeHM+AEM9#~BU-1z}2*8VZr!fqUMj1otzZ3waac{r%%MrL}k6i**EzqPePD@JWSoI zIKfSNWU^n3dhf|aI#z|*_NHG6NxU$WBNQiNsGr!lAwd01llRUm1WFMSWTlQJxVzD@b!?;tc`it_# z0%w%hOL?D-^J+GSs4e)K- zyi@+Da-z1Vg9;_|iNylhRs3RtM!ja3nc%^PO~gT9T=q#ew?^XVr~QIP?OLgE><&q@ ziR}NQhcPyz=6DPR)iTjfAA?^g#cwsN)JC?0*i8Ncp919fh<>{)1ZRaMwQ3FwxSAtn zg1yRR8~x~EsTEA0MN+WcVBp11BXLoo=5uU$Eo~Rr7%!jl3ro~f>NC1|cGk&tYI2Wt$(U?D}oQryuG4K`DBTnwbBU;qf z*zNDUwb1rd1+nzX#VK=xkZ?f;zDGS?Vf#oNO=^0s7HJ<15YW4gtkjfe^yee`Nn_j- z!_k%G|6GXSOISSYMrp@;YQ@?eXK zDVGGG+`~`L(8ewtIPa60vPJxrKdtI>X|_w(VS2`h>4MBuJ;xGiRxz1$yK&7MLVXGl zS1L}tTV9TFRcS+hta~?BBT##%Tc?l2W=UASqw)vI;i2rG{$%zMUfmMN9q9s$ga)iw zIm?v43v1r_ztnWDkaGsFmPw|}wKB_v2r!&%t?JfrTb=B2uHS!Q<_kc6SCxA`9`D;) z-EHE+yrS$S{CN!ajy_uDivws+$O8P`{wY9TcD^E;ln%qfWmllp)yO z65g{hW-2clJw-abyO2tg>5QpUGpX7NEn_g?iLlm!_Xo6}`ZPzUqIB3yMD)?7t+1c( zTXCbsj3~#pSn<`c8GxN|Mil2N2qcqddGO4$s5hp;NPyqEzIsYQjm>xpSfIw)sB!(K zG)tNNvl(Y%vASR1hbux0ke~)vGwkrJe*jICLwx=zZV6vfaatAek0EM_X8yPX(1GFr z+>-6L_+F8c&8q+6^DL?lg^QI@(AF4%KN-0-?nAi^0IZP&5B{HbRXMOF5B=g>mho>% zRT9UFX20h3*UITOhXiK=Q?I73eT&LZT+xx4mpJXSY2EFnksVb-J0Wcrm-`~m0+?gd zxUu2*5!@eoO-JoW!kK-njS=ei(Da}P?kyNZ9F9|kM7;5@>twRq1W$K?d)IA7SDBvy z)b?ikGGKwWhHV$+1g|k&0Ki`mFx=bs_}6VB2fxY#FXR%vi7B%qz|<#JAhi&m&SOa= z1re|C1w=wV3D$ig%L2=Cj;O`{MCY+K`UY%JsIa-wgn?#yJnI|FzcW_;HenFjXQz>$RXZR+Js>2uSlsrN@#|~rR`b)@Bpe2oc=-86SQVuTCU7$2 z6M#$I)s5lif5N`2t>@G6V0&4k*lMiAE-Z3ljU6BP(audX>=Nxe0EQvtBwLVX@p_^`_v0AC*TmMRj+oe~#SKNNT z-u2BBA$0=L9j1j^Qmq#lGpR06`=0U&6r{qYz=@1vfhuKu1qXmNIg#r`C(%49o#FbT~ zb2c$Bz=f*HB0QQ2$wR^-eq~5-C;cYik!p@|intV77QKOh)HNi`Z?izPWRd2UKSc_P zhxghr1iz(jZ;>z za28EsS!7V3PcqCl5L@-FyZz%fV-;3snAb+mj?2S_9cEl*DU*WKmSV|8P-dVIGDtZo zWL|tSc7P;n_(ur>HuqBho z^&tU5%;p=Mc~pr?Aqc$a^VHdO|BUy;-e&_n(YkIv&xTRGVZcLlHp5CLWW?*YPgtiF$pKau^l3;-tfu}y}px6;vh0XPd3Zf1`w2Qs84q!GR=9hAOBfW%NJ7psaT=Fbbkf6=4GFO+fytSgZWsYT zG93>%H9H-D&Xi=H(St?JqMGVwnuGp^n`ELVqKNFA5PJaHRP? zch}uAhyk5JgmBMF6;>4dixYOa@=gU)C=NtL^RJG)fhrPVE#=P6$Q0LV6&HMn*@WmP z2VxRQ%SgtNT2bwdH)IK=q>`R$kZp&*9VT0QU7rpcZ^u~)L&EKqHU2PBuEi@ zAjC&n6^|fKx{8#Zh&ahO&P~kBQ0%rI7p0+Sk_ot=%usx*II!1^mP)b#j;qDozLd~@ zRuL=KN=K%QPB!Bm_j8byz`p|t8RXj^AOeGIz_?1bwrHN(PrhPzX`zdY!p~5xK0|zj zQm8f&g*>LX$m4>>Gj7#XgS1bim=;fn0IA|2c?a2aT%c`Dv8FM@GcI?^Oh`0TJ`^y{ zQgUf17C3*)eULni9_UF^46lv||9zTwAMr5w#cM?{uh_WHPln@CfKzWEz-yHyn1DT; zPH;>e=idThZnG+O??-u`<2k!SI9?J|ds{F-9my~`fY48jAy2kh-oK`cp}Z-ZeAN!| zpr3BXqV{Bp(7jPd+|iVy8Z#~}MI+-6GMH3@iAu_3J!7qW$E{({$z9Kj{ZtJ+bJdr{ylek9=6By`z%K|no#^wprm=Ru+-K;2R zkN%eQ6kvPpqAj82a+{wpYW9+w?GU0GE59M@Twi+|5tG;;SmJuKSZMrp~<^ zHAh}@XrSeJPfy1-Cu7YUBc;L%VcmsY<={_x?9{Oyfc?38_;~tdHoIuYITzJ@g{t|M z)zdu8OZWNd5dV4+quSY(qteOE*9XPDH-z|}={3NAZ0X>@JgXT}YgKl2GH|1cNcu!b z&I{7BE=7GDuTYHJ0D7422w8_Gp@l~>uUlT8E#gn4UZDvuELNiBPXmg<3Gr4lu!oe%4^x{82={OlS-xQ`s@eH}u=W6tm7Z;kH-O(DX=($d# zk2F&&-Pqnu(6T?0>D3w4n47!Fw$-CmvuLkW=`k!pf>^{cz7ieX!u(e7Btz4=ivg9d zBRAoRRW^QrIdKaps_z?Tnd3y%Ho+4^7OiX^xM}e@I-%p0lZGS3AsCP9KXeeJIGh9}rs> z2ZT+ZM0{^p+u}Q9;d8G~R572ac^@oR+{arUB)1~-($R=yur6<<%_=BSYqlGvgdox0 zez}r&t7f*e&n!u8eT62MUeqU7b{BJ7@8u~bd*!JYt6CMK%(Wx_C=QvibZCsY4IJoB z0zVu1Dj88bXLi%jqbq%!A2a$!cC@^mt-DfvwDen;hE!o{V>x@t z0~s$nnIGk&9H8>LM;0{ub>+>TD%buhdZ|DGbFxn1DI){vCKnnr)hQmNJV&)xTkJ=iH#&6j73So9{49_+iXmv ze_d%Q8)FZy)GL*ewGO>na8pVH!OFJS`n?m;LjGQ*XNi5G_*qf@iL50Q4d=`S@s612+rVer-FGnXnxA-P*o+^C$%GHdCLS93;pG=;ROS#T-s9}#sr ziLQ>wwo|pMD3lE;BevP_z{f!5kPRb1v)gqFr&YJZE zn`kpzPSv7C#mYkxg_Fp4{&orDjDBh5Bl!VLo}cZ81pfmN5A!_3P~ zcY!Rk^)|0+>=|#Vd8v;mzM;ZF6&$9t;cGN{LDK6zPY}}6r*6T0g%%eKYwZG0Bc|l| z4X;_-k$r|Q?O^;$oyep2qoJE`ySFL`AIzy|(6rs;?M;OT#N)4^%fG+WZaIEhZ~$gv zM>6wui9=juBBjmDhgjff`L*L;eN>q|{T2eqwAQWFsH(Pc9N4Yfdzi(+qaedmF=Fq> z&NDZ&mlca1aySeWo7@_T28y7bHDI*$h6Spi#^SdA2pgqQ-yU}|!j~O7TJ2j-Y^ofo z3-&t5RVlhdO($vYVXPgp3psh;IGW|&D>5)zAe z^PLH}CxsM%;vOuf!%AUKjLM1|_bnUl?%lZ)#jGsO4s_-vgk&41(zDQehS=rt7VPT? z!Rb17(#}0-C`oztHL4dT!n-_uhBF*Uv~(^G?^Sd8wtvE1qK~axtu_yj>is@R&X(Ko ztV1e(xL%)?tdg)ttP&*+PJ-E!({8gWg>>E3t8l$J>I2!pJR|NiM~tGUQ=cXKdu>Lw zB2#m_o$&V1^kWmIt?|_ndfi?`HrDPDX;)3te}rts!+XVf*SBO*C-&{TG%#5sz|8_f~ zHP>wq$54D;)s~1bn%Jujc>B29T89Ko4c8zM@w34+i>ymXCJ4$~xb$+J(h7_KLGgL}_an{H@)r{oP7qyy@3vw>kVgttW#rdSc|Z`?V1ZcXHDB z?y`EtR{g%Y2740sSz|F6Qpqo)3`#q6A}|aVAVX$7a`H_WrDz6~bgGbnmXVV|`aLH- zgDt2AvIeL1WwskjpbDxKCZhw8N{?w&1ncB&*MSpS+2_m%bM^S@8xzMEFY;=Dd1bOV zBF)w4WzAq2gvKS4KkQ`nltm8+McpBFa)L=$u{UAuHkB$>z(|XoOv*i!>W+`9j3Z-J z0!BT$&@yUdwbE&yASzJ@fhG~X$Yy}Or*cw2?LI&zOA_PKoy%@*We)@CieC-x`8c#2 zyZW0R?nYD7`dvfq=3XK2>l{H&LsD)I_E$9du2Qdm`LIPf_nM`uFRk>Feh0KDHhN#; zRO#ucOzQ=y(<5B!6be*1m`hQ(3Xebq#ymeY%*n&Y1^)0XJnMM0}Zq{dUz%_!bOB@t80 zXo+&}?_)Gho)DDtbH^4wjMEjjN>XC_u|PV4H-{s|BWhy<<55^#3Q`b^=0gy*4k#Rs zVK;ZmV21io9r@S4Wzxhk2TM5KL!NjN%VOgCb<%`Z7oLXPVYP`>_Ms>if+nOf$7Rv6 z4eZ$?c$dp+Z+3ICM(Tkz;njoGc<#>KoA9{xztvrtsBBX!e(UHienW6;>Ig>gBpP4I zkf>505!p!4Gt{GwfVs9MW5Y^YV>ZKMSPz$fMhu_HKt29>)m>{5kPTzBI@#ud_>G(1U|T$i9$}7~d`u{+QQ)vOdG~8z z$hA-DEBUxodjKC&SGt1}+O)|~Gkx^^JzL!EJuFCzsR!FXCj-Tv5S3T>gl$8fJ_YCyWVLYgzF(rgbp^NXH~DAYqR?8p>29RcQ}K< z3re_781l++=wNhopfuEF_*n3uFk-x&{GCN9-To|?Hs`Nhjy`o5`e8DpQ9@}nEGjux zVwzF29)M2TY`yrAjG89ed9{hq$9-tp zO5xOT>Pd}ORTr=IC{|3x^7OoWdUc>*48-T5NZ3{AU>NSA-(@O4;<)Sm2^DpbKH*3x zWL1W)V#HdXY3Xe6(wqEoxi5nAbFDGfPCK-wxsAgS8pePRbCNmw5E&OVN>X!X&B4*s z0=S7xsq)2)Co}{^QtTTEy;+z5-t?lZxV_<3qZVvC^DowEqZe|*Use)E)yAr*e$RrOGW9oVsN^2&XL}SxszLigP$~i} zc<9f?#%J%ja}Iz(d5eSKP*>7~$B3E@+*&Xn`ZgmzS&lk%qrLL$k3_kRTp*5^S89wf zJ71eSpNyIBu-;Bh$GnTcd78C6KTcm?qwG*iUhO|91E5gt*fDH9b9%E%I5yIeT}(pJ zLP|!msQ>_WQjZD=xl4a8@7|mqV&kN}F%V0Onfll(=t;lZyEUgiWig};N{%}K?7J~x z;9LnJ4v69x69k*~o^)}>Xgpo}y*yN;MyvaKkd4Q@+f{0PqOr@g@(Y&3UDL}oym6(6 z9pZ?MqfEydsUcLo_#1bH-_N;O-1AxSU z2N0Pp3MP6ix_yTdm|ACkRpHGiU&>!v4yTLYN6M&Vk@`YSB?k=_Ie!J()YJH8M?{0P zk4%8)X+s9>>{Y$Cz~MDx(61_fh!#!%Ap_gqId z)o{$^&!OZ_CNGy9n02xN!cKqB;*w&Pqy}4aBP>U<9O71Yu$}Ty9eMxiLl~Uy2a>E~ zkU+qkF_hh~@SV*?h2TPXZ3q)6ItE9U6)&9lv3~2lKpAOi=2ZxkW7XnQEZ0yXEf^Ub zpYXL_)kOz&p*djd_L#M_+@MI_FcF}J1_*g!2b&?LOoY2q0qE%C=E1i@oood7g`5;d z?Qo;6u18K+rpSuNWe~JMjA$h0N_~X>sXMC5=^+fiEcOCKxZwFWVJeS~=TpRgY|wZx z1a+{Wrjl{X9bHz^=7PV)v5Z<4(Kapsy6_;d6R&d`FmpYw_16aE#s?iz=W>iyW3Zu5 ztw{|ggkjy4zzV#u8oBDe`m3@q$16q%B+tasx2BDegs+i}kit$Hamnx!t@CAWJZ;P$ zh%-&uP*+#D5|LUJJdcSm_Fc)!TQAz0*5vqMsEhOr7w_tft*kU`i;~iQIMF z@d3eE8zN~f{a5T&fj&1^ntOL_t6%A!Hqx)zQ{b(Umb6roUiXWVFb?LvB&rwVkRNV} z$0X4eK_&Q+9~CMaboS1ov0`)XdDGeB=M;m{71lJ1=lq_{@F)a&qQT{jX~n*H48exP z%JQ82vbi(qkWUXQg?h3NVlzix&9!#WBzw55>5_9-BA{G+#t=UBQ>E&&4f{(tpaXf) zewpC$cCtx`fErF@seA0C>X9Rkyk=#wl72Q=%EWBVv#Yjyg$AGh}?vy89iH^BQf=nu%_7#hu8+j_l z!Ipp$!Oxhc-rAnv0`T!k#^CcZfC~lPRDImwq!b0g2hMWTL_w9uOn z$qoV>GfdI;kn$;a|Jh=^O!=2HtEbcPZ(myYWqHnSj)J%IBXg@h+ zane>b06tgUnPqP>!z{<)IBX!E6CxFXniZZxbB%5a<&v~lYt^U;FATWHvi2y6oj%JY zE6ky)hA2g!a|}X^z$0sl(F;%_zM*~fUVPd0#RVS@MwwpV9=>h0hF2y=B#@{Sr`{<` zupSDC=TaBbK}x1h@{N?kRgwBF*@B-;9jB3>Ou@AzrEg|5#O02Pe?QpDq2GQ`5do_2 z^UeoUW@PWD-m~}3X^xHYqMS3fzrD({Hb$@_4(|k61=(00U3SZ#9yC0Msk?=X-Gm$u zp19I-Kn2eDc?U$`pUGXI3#hG+@f(lx8~anR-89MZ72ieQAATvK8f{7@cNC)7PYPtO z(dB`p#%caV>80X-MxXVWg0`k+(Br@gyK}WkWDl_bdaVsE|ib(gxmgUuunJ z?nS(m>xJ6GnPdaub}){wc9{004dJ(?H(kUn#LThg=rV0AYAjMs0-EOEqK{V3MHcut zQ%&c5!yuYr@CpB7xJ(B;W`k@c2UMH~?$o9AI_uq`nRcTCNg5*CF%IjDX>^D$3Wu9;5l zJ7%s=2HlN|*LKc_H|G<|SCkTvK285yjfN1c@l#s}p>w-PLWhJ>WlIFdlHjaDZF47y z6p$|-pc0Svn+tms3ldr(mzXnVh@zzWPOQy+t<7-u-`$=N&$Kfgln;z%3yACMaO{>q zDcIAdfNz+z2^aB=V302eKjc6&7v7`E2b;4>xE`$)Q!dm3X zOzHy7b=SN~wlA6%JJW*snG;RKr`TBl8w51S7?bcJCLu~a!Y=;wa`Mv5F6piWke0DH zkUCPh*kS9`X6ARR>#kSXz|-T1#`lf*5<5z$sDv>zT(XTcQ2KaP z@n1=t)+b-Ac|>d8y<=UT9UR6m_-5eUdhF5CFdCl!;Y2pK_!vPSa-mH8fuIMlz0{HT z?t=ImZ9UUCyKO{LrNZ^GFP}W3Uf5D(qVYTakDWaLvkL|n zg_?)^r7g2P0CwK<;cPBqBgQRmsv93|TD!!QqmP=1imlrf#K^wD(t}rdjfiQxC$wP(80#C;oq z!bN77?sA92Kwpy!2kgw69L>kcPq+QvRKIpDcC2Aqxv7G>1R5%<)Z4ncXDBV5w_G@z z&bPNeZc4-T9;-GTaMx`tvwp02q01JlnSRmN^MAZARBhVoRQ}GufznDBa))~mECiwO z44FEmiIf-99D69Ah=j7#uXuDi&{pDJoH(T?D_}Gs+1(V|-kmz3qXd+@{henkq{fGt zBWw7wh`L??aDq zA5-&h?n@}10-TXXLNrnXjw}G4*&rz8Jg;8cZo0{aA=%pg2jQ5O ztoXjlYjZKa2Cpb4|7$UF^?6jpM8FwW7t%eaInb|IEO>c#D?PVA`JO%%`TfyC`k73n!;B!Ji3E(0NdJ4U5#<)QgC+kt z$nD8}J8Vf-p`XLQbYMY2GQ%ZV76BNxrwBKFQae9d9&m}Yfx$MWV5n!ZNIxK+p<$-$ zD|KCtW$7jMMn74O>P0OdnWd)b@V6%IvExGN8?oIvO~RIFdU2C}*OP}YM-n}4Ck?@> zGVp_~h##0m8=TF+(PBQjPqH)KM}KyhMii`D&sRiUecWr~zXRtBu9OiT7toQysAkL6 z=Hj(hx2N&Y!Oh^*%tf~Ny<0V6M%abHlA5Hq9nTycpc+PgDysGlU?y;rq^TolAE!Es zTc4J~s@;%30Nr#cT$i-LgdwWo2R;vm!xmPJ+4$;h!E>MruKuJdmF+@j6d6XsQe`|K zTDYkQe8&V^oFlz);W4!#WK^8;RS9P)c<##Gf}$*{upmcI-h9%t5jj3#MS#=>bP)MT zf7=+5d?t^>`#8R6Om@08T1^bcs3tv}?F_W)K~`Y{sL3zkfcc$#6j+$PZRW?e?~{<5 zBza@;-MkqS&x>jV`Lw?%AUD9DMG{hxVC#HO#QT_f{5W1;pNs_IO-se_mIex7$yyV{ zxouEB4>u2cjcCLof2`W7qu`nyu+?wl!lf7Yzb_Lp!TllnNbI0glK)C0-kKw93J+6c z-ukV_3a4xUeprCaFz`b}rblWz*^u4}9{fv{V8VDn0L_id_4U$Yvwvl!bIqpTyZtA+ z>cBYuHp38|35ikgS1hlK92%Ff>0>))3_&YNKjphdpkpxLA^-T%JX%IZJ zl+4w4W;snY9JYnsY{K!f!Xv*T-_YbHB#0=~e2$2XBK%Gk_62zheG5^RpY(1y5&Fim?SYJY9g8)sk=nl|a`1lu~3yi5Ngx`L0wCUS`5 zld9Bm#~IB_w5>GWsfBN)WOP^8%oY9H=~E6R)Sat-m@#{*ppHK4b;_1Zg|9kn&15*j zX&7ybh$-)GeOHg0F&DY2rwRf63wU{IU6EEGi`mk+)d}>|&PC6mn#w}7XF&hYG zMOYOP+Cfs!-gx-7p@jX~(|4t{3A&!L*t z@wS&cKl}MPz+jJjOO$@h5YX1qR)K&q=CF%^Lhbz7TQnoh?V6v&P;IAxNcX-uB6O&$ zuWMI}aw;&FKZj@&mJ<7mw&zd&q~)$}8EaxNK3tXje#HW{O03Ov3EUqB%IP=xvvqME zx5U#8TF5FtjW{^*&qcG;h+Y1^O@e3hly`p`=zcbe{3U4Fxn1(@fHYDWTC=a0fhnyv zD6=-Gk=%o9mNTO&-Xe#Bg3dox_|=h2)D8vCdHr%QS@?h5<96=@k+x&dHgw@!#xge>kS9{Q4{`n zjQkWjTc&&6E2Xs$IdRU|&ofZcz?ueqOeQj1(%*hCrJ{H@o z^H4)4B0tPdKYqFfrUWn^O5r8;k30kBnhd{NPu(!JsJXM`7>vUz)6Ne^)9w>R5PGaH zglT~mCR87rX zu^yu3VQXn9UPh1_EXSJxYTd>;S*~*}Z4*SrlCK8WuV*E;^2^BD%u6hKq5WnPr@h=lr=t zIkWW62=;q2H8dzE=WoAq^E`GjXEQID$lt7!Ms-(hjK@cKpS=txfo;hNzwbXJ<;su% z5HfZpXoD(?94xLs>X?bz%DSfwF%NNr57Nu#XTva7C@##UeCgkf!mw{cdZwT{ra028 zHFvhTciA3i@MsJrWLtG@vfZD8)lW4wXk3zIx5*!&5;0`4g3e<Nc>L-545Ka*7;eZS`ga+?Ii0rp>p4Vb}x(_HE<_PnVr7Ephx$5S2M&trh z?DtQJBt`xe-qcLv?5FZ5-97gy?_?WFFR=P~ZSy@>|2-UunX9U$e@)|-eC6kwZ#CK9 z_K=G|@;Uo{k16stvcSGqP*Zg-zF&s?!9C4z_i$u;YY^Puk>LD?shnRs)vliv1?!i`ZrcoOPkaBk{4@qHOOIWj&dho!@PJLvS4A77%X^uI+4 z_2g$St|}f=C*UQ*cE`m7^6j}rcu26Uhg50%ku@GN46lAT+2aOs4jJV)`?j_L;j1v4V@-4$JtWmH}mLHQM@>(blDYxOf#6{;j)!cHbbEiVssKDy@C)w2j;0*4F00` zMY>+O+eH7T6-wi}J(Z7JELk5}4QDNBD%4Y!?zGz2*vX;7XXQ9&N{BK)UI}{1e|Fk46m(TR%5BQuG5#kS!&P~>A%F&v1 z!(`SxAH4Rn%l3>n8x9g093Zg0m(b<-AxJ2Ox5u`{dZB1MA4rzgHSomIN#hnYGhQn6 zzS_?86XjLad7Jky$QFhC7ygGn%6vOaHwx`Z?}M4l&Ps$k?2Qs-=OR9zjt7^Rf}>3X zR?ml5f2WM$4)-wy4&3=CNEq`?ROx#xq}3QY z1(L&T8S<4-Qb74CPjQe-U6!wx$#sLac+KC;6A0i@V~*11 zsKyX&EEVs>Z*rXd1phl<^ZPVZ-nyQMOsuw|AbVu%kx0+>_~7MvSJL!i)PX0foA5NU zAAPmCrlSWrS#DgQ&NBhJ6MQ0f`8+)C{TT`keE7-8=-pQth_1)KN9t{Q4>A5nkH)`c zxO&^f!t&<;z5m6d@i)r$|Hz~9&jEVIj<(JYhQ^M>te{iu|DQLp{96>Un5~tqgR-5z zp)o%{lb9n5JMljpg3hM@KlgV0r-SX8WUTc~jm7?6WVD&SC>mH88#;l=%2>0ofH?o7 z7(vhv(b&f5&Hcg3^>4Ao|NHD`=af*$oau*wz89K4u^$Y7|m!kgZtRb zbdj={cRAIB$SAa?DM?x_Z{u$Dw23H>ynpaSu8-{loNwdmuGZT0Xh-2reRiA9hz>(? zpvJY60;U!86X znK+(q^k5aI!eF)3IGDJ}`z=$?6|ecURUF>8Aa|tF%KUbATzvX;>$=mexRY$-xHP>J z-7c7t9X(tSwNoLR5l(lQOV4Qa%Wn;a%3J#PF?}=}OnewAV|YyIZ}Rjqd5Jy6;p20Z z{GSGs^o->+K1S%PPG1`yz0ij*xxa9W5H^1%T0{HdX-Np=d9sXtT38JwvpGvkw6|F& zSO^x_Dy-z(v{V#zT)ZT0l$V5=GhG)>L%6ZtIveDW87`ln(6fj>b~iJ!Tmf_}afsyx zT^+?w^{WojkSMAe)YL_UUnC&&IFKWyPI^kiJD|Ezr(fuU&cR#X9qVr9|8`4rL%+j% zPTZqr7e+>c@gDvn!E}Is#nnwM{d&lQZ%+sz_Ab4GP~kAZ7C-JzH)|=_9*PdtBWhD748tJCXbMGE5?g; zt`o+pDw3LBvObyPF*vgf6Y)}}g=v^mGmKzyMm%bYUCi|Ja36baF>*^3LB?Vsbu19? zeJFkK1LL43XieKbn+k?#`P zL@r*8wU3Ur-=3Bwhctm*B20$=5`oh9{7O5Bxbwrq)V3g_z_6|9snj}kV=H;nRhv{= z^5(nCDJ+#x5|N2bs;z3K;itNw9v`CR*R1W4enDpDMtliKhD{7eBcuXHARS-0+Ww(48GJ16i18r_?%2l2N; zZc7jL^5X=y&^)k01GT+CJhJDkClZGRNtGL5_)ez>skqH#JYbMVI;AMC7Kaftoi zgmfK@$HWxeCO-`8hKbe0v3!#l7)`4de?YORj5HsyO<~LxhK=Sd@+UMijIgfsA>^=e znx>>RgO19;HO?vMq0OjLFlVU^4+1ML0q#_%e5lna))tget2~+Frt^vr+osATPO{bj zlnFSUII9E8Oc!g*o5m*nMZmYxVfX3Wc2r~w&Ck}Ay?BZ!-I{`q(x3Tvhv=|3L#z}Jz>l-&#bu~ozTsd6viR@v8olijXp1q=T4 zL363KoRev4OAaEIdM~yytjdJQ?m8RtssU+`U(483>oTF9o9*B31YA>S7A^Ec`PwD< z;ga1inU=?g261OWFup=F^6+O~9>H}u?yYm7$TW8U&cScmUrF|B1QV1E@2{y^5%<5f zG4NgUvMmh;m3~{x)&ih^j2eQyyZ^SV7;U%MxwB)$xGgqBz|v%oX6pjRUW>MP zXJ}pn!i+}B!l~h(PxjaP#gIhD(|j@s5f1zQuqQ!L5LTSyq87_&HV zAWx)vrvJO-tOi<{n}oDf8PJ*E4oxr~Mr@4%6HD~bm_$wyCTuqu-K09!VME*;W4mrs z%GqfBy>vG3i#Y00P&gD^?L?2(p%{}0QJ&C*YH2aj!18l@?8o)@;O@jwiMjWQ86LsTPL=2MM`bNef-9 zDIl@?W!D`)tE4g!ZWl~`PzVXDfI8ZAMz&VSWY#XwbM*s216(A)aW5M81+KGZ6=Dy@m0%Zk_ibN=Y*(&WNZhl%A#sD$vt z)SLd@PGK>i><=~S7i}iU6qMr*h0DmVrF`B ziFTa1k~|%!cCf*zG7ggF#IX+N!8#&hdfD|Yd>$1@kfz(v+}ZbTb;yt8BTQ0g8DrU} zaM-aZ*)2|UB*ktgXYGJrbd4kI;aHfFhAoI{#z*`D*J`x6{NOTWS@}V$ks^I*<0@oP zUJVm{9pg9GiJwi}DAPI22)@Kdmh;$2g!l%%;?Svmolv!mdmp6;FJsE66DfdLOW>C+ zlR`2IHHPvjM9!*NP2gkQqe|OgZ$T7wqvpYJJ>aJoCt_Lfe%8UzP%c;=GfAOk>fAm2 z(V-|>H(@)Z0$p=Iej!`UiD%kLqwt9*x~8a16YaKrvj1uy&dZd%qq%zKX!Vpiqll^r zll+SsC^0fMUQy|Pw3zub^LLWhEgYA;^f}dAcB_)xO zkwL)^IfRPM|4|G79{gbLrV{=n8Ct?mx zPNt8>Hl|Ky#N0frJWR^Y22O5v#(zyQCY86p|5#&8YUV~DC>9pZ|K;2A(PC(GiAGX^ zejt5J-^%s`E!wxRfsmr3$FkPf_i`voN=oJlB$po9ml@?16g4m-KFE~ugW_itE7j`Auj@1AQC8m6td&k;J@M~(DKb9z$oA>LO-!f z`uZ9D5U0T<6K2`a0AfUHg|xBtNuF`!ltqLk~+bJDtw?7QM=`3CQ< zw{DWLZD~s!#+<@r^M>h~5wO)<+Dm7<_d&vP_XYJV?etH%^9J<-xesGQ1>b7hS&#yt z&OWn6s#C7L{f(dLfn4g)xa5f(WsGMn!Hr;QQ8L3nd?i)@*wvd#u~x=t!gi9u($FQ$ z^vK^hFOnq*^Ip0p=W%Rqts3pxo|P$x+ZnmPCb#$Y+1Rx#QEiOgj%p#(u@xDA zgOiG+U6^e))_(1l{v(+F!MvJ|5?+yT!(Hsxl@lrt&1WiMc|*%LWpTj+*j*b`!8Z~L zV>UbovigU|ZMQ)Y^gJJRB7w{Na^IhjGQF&d7Vi?Esw$SsQcr&Z3 z25T5&^xDUd!dg!%mOMjIn`Qh_4s|r??q0J{do-221E**9i#m{Fy!JIductj*V`zKZaR(1t0_vLIEt6UYTL^)d z;5fd$@idH}*ZG-2-qBfMe(soQ1*SLF#M$9a9`j-ag5JC2jl*|!q@ymM1mz?FyB z`WKCvS~oNd*U1@7&5{sc_C($FX#jPXc;?&tVlNH>N}PXkHxFDt$ao(O+_Ss?S??}~ z38-tWAXq5qkiei(%y|P;L6wMi_U^lKM3*=$1h9j0c1W}BdCT>C@))jKP zytVjoFO1_!JOS@bLJIATl$En;o}Jt8(~6pfx0YHbYmLhjJb7^qM`6($myKK2gGN)d zt4h~Y!f?Mp-ESK&_mO&`yyo!nQLKJ}x4{h?BkC~0Hn?qZ;+`@3^0=y3Dt`Fk#^no8 zTAvowiF)7Q!)l2`LyuWc)Z#wQQM|9-WTW4eQQ|&VpQltuYI3lsPw-q)%u)eGjZ+zQ zaJoIgVGBusw8|#wi*f)$VG;obp75t%b*`z{{^`Nr%|cm09og3`v;x#^zm1_Kj$woQ zf2U{$4FjI|3;<|cvbAor&=SxfLL@Gy65a=UhphpW0>MUqr*QWJ-GXTVcR{yYxfJej zk*H^%>%=QTL&r)`QV}?)uDn@jS`O&eH>rpPm+ZT1owzlKKpT+4BD4>750wGn!7eGR zXco!~0&+j^Fc0OeDSu^a?ug$H?ZvVwW7hyyM05}?>ki&n=Q!1vl{v`@BcA3;ANeM? znCf8z!~);(1A3VKL^;UAI+=k%2zQlBY|IfwIiiqR)CSlhIk;#NZ(#49)J|})C8v~5 zd>aspJ>CVOawJrCP+#QzEfoa9B9K{7g8`sG4={YGA-Y3w;e|22>5C&m6aPUBf$|3r zcnIkmb}(_&H)LS{Q`L%yg4^&My_uM-;;=p=aXcOQQiXj#VGgt2v7sC#r1EHA0CX!N zeFefEAmt7ktv6qi`*TXoYG>)HH=nqm-pX3uN+SyKtc8*m@kJPnDBkF8SB&_KEFa&G z>dp$VFT~lyUwuK5l%0;D?&^>9Sl|_8k{cP=C@_m{ud zp-eg!r0Tmyd#UkgKE;<5-HJT>K}DP>u@ zxOu?{Z8hK}2-LtmNIdt&cO<<`Rjzrzv`!w<-}v)FnJ)duADSzj#0CdW_RP{55y)wz;l( zT`RUY^;#%`9omB0wG&+;mt%pNmK-oiXO{E4SNP)e1ZqKN_J)x_12oK$Upg9UMgq-4 zh6ca;bj5(ML|hZpv=o5u>6wD-yWNF5OKFVt%|0B7ZF1QYzqTd+diRH&;^({FcCLp% zTmdA<<5x^F5SyD5+TZ!Q7_wwVDwk@X7?SHf$ z0jP5gA7NssrMi^3wQV^7V8|Z_nBH8Q%X3O&L?)2}Kmq15etY?v`k_D=iVz4(6OU@< zsg^e3m{& z2+$+zwaQ@p&hiV(THy~Lxo!(*lJezup}=v{u#&KgwQOVC0#JX3X)T`a@1`+3M`hpw z3Fr=%ML5^aYz3YFq|j(Wha|ZRPEN5(oghhi4+aS!-j_ z@jslTy4$^`ou*q%o!N9+M*H|I+`Wsb|EskUf~bYz2EjUolBqM7&UD3>Fq28Ny1zOD zly7|=mcud%N+Y6C?p_2x6*zQHOZtBO7b{^1gdFk_a~&T94No14li~L|o8kA0BYO`WDWiW2M`4q>FCzfo0-}aV{NE~HEWdE9J*Tbo z*G0GxO<4Ggqjtl>Pggl~s!0W#2U-jDHl*9e{2h})O>DJ8$ewk93Q!7aMhIloD&1+| zJ~cMBu+@uMnLn0^|BmTpcxU4undtpFt%pzUL?S_LgC*j-65=6@C&riBc&zk=W@pwG zAC)alZ~uRx35HyO{qH{W2V4{RYm-OcU&SE*8R4IHz?ob}?|^I(MeDaDf5!J!{OCRJZ$kTkOKGK z-@MVB=Gm#P?buPI38TE6V6(V`hSWL9LX|+s<-OOs-kBg=mK@KbeyD$wG=ww=P!8Il z*J_9Bf+Z3Bbl#OpH9PfdT;(44i6epY4>9uP7%8(vddB8VLfY)_&pJLa8d!{HYVAc| z5CaiG3Y5f<;o3rda9+N*-DjP*W;Di{iF?_5fq2#VrRwvSr#PE2vMa}^ScmL*sd0V0 zU=UijVgMLI?e1@6Z%89J>|U5DZ#8h>(V@=n=Vc<~x>lX^pdn=1=qJeeN~icbkz?ZI{OQ=HG*AK`&Uz zyYrqvIiJofoZI?l(EoZ^z9xME>pscPQ|e)YXC-ZTvg=>$MneDbKVMfw^!y`ip>@9ETOg>Y<@X$e`#yvoB38BDx= z4gpbaTy<>~49%xuN&8Inrz<-5q^k~gG2EiVTDu`14u^WH9-Dw$Fu@y6pDHdS+PBw; z?E`Q_FLxcbe>c%H(&~z&n-phz=V=bNt*|57~2C#!Z=5qSs(1Q zJ&(EXZB^O_8t_3JDM1cR&>qUSH}0AIaBeQ!yK&wf|A+rJE7w|n_jLIuZfC5$WYut- zWY*8z7Yw`MQMLl2LbE};R`~Oq~h}p$-q5^~7*efF8mR^H> zE8!NMLcu4u`%{8XVgZYU_O~PorHBLu?r({dG-tmv*8OJpwKtl@02Tp$&geYBvM2_R zII6CbUBJ6DKG)em>Ia%tFFC|}pg-9aoZPJT^9P{WDKA6AR_4){y>o_ShMMfLtY=Yi z)L@QZ`gL~8))yUe7zB$F<4y(8Iaqx6NvFlC-L{(o=fS2O!f-I0Bl=t1@#)mO?5hJR zmyum+%d-Oc7OuC zR7_9-P)-GsYIS@KVtl601|NpInzQG=$#OsmN=8!uI^H>X3T#j?MTXy@QRznIUjB%h zNgb+WApxklIS+)hI{xXvC8kysMAnHv-T*r1)aB$oU4-cCxZ>$7FPem~X_&)8(bo&pAVQ1?U}${M_^6y*IiA!wk@eD@4;Lu6>Z9xSuFq=&fLnrzZCrnNk9xdyl1{+(StR1@&F+gmJ%_3w$wX2_0?E(g7nvQ)w#sh4z3Z!ej~- zA-6w^!M?6&-7%kyU0LphE@|xJ3naEAvi+tMa@aS5cQS@fURibG89CqduRgLm9N6<6 z$%UDk$sk~cr}dzin(1K+7z>z%BV^*X1MPxb1bOJPaxxW1ewmv2>@~*h6TONKcHnmx zbzS}Jm}{0o)O8RLd+)#XI?Gm9M?#yK6ZpA5@Z-y>(m7Ken^`10P3AR*o?TeFE!Mi#IOd>KZiq zZ%UW`2L2)k22EeE)q%1%{T>~=a4E72nrWgT4QnUrE=tQ$%gD_v!Rl7(mc7T(AQaJ$ zQDrGTx<)AXP!`AV5()w!I=Zy9Qcpm};Y$G$edAp6Z{exjfg>Gd-{|+P$ zp3LZ27qL%Pz0|A;wQaP!Sy%}0w4d2sk9X3KS^bB@1;c7?5MsWm*=+coe$3M=uS7!d zCuDh4z|}Lhq+!29|ueWHJ!Pn}uEfkbE&RK(5OZ~)ec z9OQx+z?S?T^aE7BVO^!Kq+{e2m9LWqTCV6rS$v@r6r)>lck%wDfgH=fpZ^c=b=kzd z`UGjB&8@UXp7+0CnNmh%OJ};jJE2=S1kEUdBxi{bMm)rM%}dNmUl?|GKFoeJ4+G6) zs733LKJcK%xUD-hs`&a}phS1KLdn^${XR+Aud_neS0Zlgx{ccsF7Oa4&OO_B>yY;A+ALHAjt@Ddr>g-55*Z;P%2!IZ^ias5TzIr z=kc5W{a9jrCo^8+FYOs?jPjKmnSXAM;TCSJ|Ha3$f+pX8gEg4Uq@ z`)CsOd}FH}t9|B40g-@LyjauGy3}Kt(*EXA){lfP65(7G86Y#f+t#toZ$?c>Pr=L5 zg;nQ%nmWRVBVmewVCnis**ZcDgC+!bCOX(t_-IGqV|>c`$M?8Dc>4xx6bvTz_H2+( zwX{_0D8ewr5f3qvxEVJc<85Zg_;ue$?AV4Y*xQl=ao^8spDc}v_jLUOrKV}iw~T0+ z#qP6kGc1X30HHzFuT5o4t+L*FHkrvcl(vg*nyBUJfy?hWQDN} z#PSVE%iGCf7Gvx|Da6ABAho(yoppPpw;wf&9ky|yiGrYgTWeF5&!cC9f@a2?V2358 z4a06=UxA%pQX8wH0tD4IwJfI-523^8ILMQ6=JgA3wYVY3&Nk+r;dtZZQ^k`j@d5Ha zTgG2G1G3rUL@U>vYqYC}rhj^eQ6uAMLzpEj<1lE~ZxPgII53X#u03tli=5M)EKVm7 z36`&(=oEGg&#`Q>E8(lp(4COZ?Dw#fjm5)<`*;zTu8k*g$?WM z-`AMUWmo>v9aWbbl|vt$_o{0s4FvfP?CN_4J!3*w*3p zRUC{gSyM00Q4Xe6I3WKR#--Qn z*{RpoN4rnW*Be&JTRrRU-=3E)mIR~8jJ#@5%s(|+WwQ(1W7Z96Hni}EeYm`Q|Co*l z*PikwNL!m9wWBjQ`KBiO zetAaDTeR6&3p{~J=|=B~34SJDzi| zA?}}|f~a-o>_hc}GErvGT>S`z|#W3fELL6268$;vQqvrkNczYAqMLjlU$ zI0=rU!M@d>K9gYh=6+;mu$?0a35o<^D9VBD&L);;hMiZ?(S-i^6&6o0TydfP9pR@}{ge-ALRY-k=y!3r$TwaOHwn%xQj#PY^hNClu#+ z`}MJF`e_HVUmrA!-SnY2VJ;K7Pm};KD9qocx1&;bKSr%ou~98G@$u>tH6(=$iBf{M z=?wYPPMPveXLxv;__$HcViZj{sMp&m)z~yLm+QM0s$zIFl3q7r)^~+CJa#wihy^%!wQKYrS zF+qA5q~#!w@eLP=*o;!*UR0Ut0rqG*!)U_`0Gl(C+>JDw+Wi;C0OYqHVzs>wD zW_%lM$-6!aD@(k1M_oFb)Vz%q-ESHsMOc`5?1lSYbZpT(<1wQ?Nxd*ERofK{Y6Za) z&9@+$i=#3m@O1+OQcIz1*!HF%NRidH2{dMa_-~}C- z`trb=sx9~mGurR>Ro!bRZ-Ue4Ezl(BOvx?rK+W1tx?p;Hd35*Ng3f^A{R-4uqk&-B zySkZ=FAHhD=ExBMe`|Q1SuXC6wMD7UmX^SIC?d|;@#)uH%c-TZO@YE_#m?4>SN<>P zV6=O@GenAVngsqfz;tx5O;Z=aQZJ`!L4;4}V9;0g5Gt-MmQ&pswS&e0VQ6ip?-anaRLiz#H$ui7aN526{i62o zr^7u*#9-?W=Df6(^OgXjbjmO=%qzBuLQJfyWABssHAZ$}XaNp_+ey*rWWn~RKnY(6 zU>0zoaWRVMrq&n;tK@5XTbHxA#qyB0x&O6=(bslN6JwdNY(~J`16H`=<=sPZU4Ai> zEi!n>^rkSAP77DL^co>VOiBMY9j$S*MYLNKUllK;tHUcLqroLHFwtwCF){|9Ek)xK z60jV1g1sA>#Ue&$WblEhL*Y@Ty+g@pydT|gzSZF-UN#H}Bd@oQOO&PM;Fwn)n;s5` zuP)VwQsSuJ{k(IjQz?F#M!2J)fLN~c=Hg116tD$wQGrQTu2z_#sk13wAwi(X_?#ml zYWhUptTMf9lwNMn%qD&4JnR{TpTq>G<%ZL(-@LE6MHUtk)4ns2HT2Da*vg)t|EPuc@NVuF`2L+di#B1R#94@+HA4Jf09n6l@US+1qI?SeQ6=@~(M z1Sac3>?O}VwsH$Ws-V4Ny$!!)6Q=o8nKRtz{f=5WzRVa#)StJ;pAkM(E7)^Dzw8tRNXqr>_#z{YDKpuqklsQfb zM7{gY$QM&hL>2403vq`bC(hNikMo^dOdNI~wHAUoBHnkKKO+l#tUKpcSkm;Jo>GAc zbvq;&`PsX6pb(!u0vLjTs-fd4jxU=K_DQW6ODR1#!Z5DYK^l!E7}k!Gx)HN6;u}Vz-n8rDMN1to0t4ArU?4LK42n1m3|1He90l}=?f(b( z|6C7OohJjcEjA<@#9+*=Q7_ep@3`NAHt788$Ig1(Y(fcI~Y{$Kt*lX)fU1gpPFg8EPUZ@AwwPrOATfC3amY;0_u95q?F z|4Be9`WDCWC-maq<2bngCX@J|iR0k@bF$n2eP)V3?EJ%`sI7yMv4iFt)6CjT;>M0n z)biYnJd9i{JRIDN(#HBm<~F7*jLKHV#&$GJpFn{Zn(WLhj36?c?A(l?v>WW)ER1ZR zJ5Clx9#-xD+9LGP+{W_n4xv9v__yGUKOFu;{eL!6MEl>V{9E>o|FFU7pIuFCT&!IG zz8fq+eKBfr0QGM!3~c*(c}^y`OJj8IIc+8@2DHw2m?-gK=A?md(rz=4IBo;C1q!Mh z&Z$FPohhX0Ud6o52P)^m9X|CtHm&Y0tq=N5^bs6G!>XB6fin9D12@}f72$yOG}{{WotcKAJE$HT+V^g7a=dX9n0JH=YUADd ztsRM)!REN`lWS5Rt}Q1cHmeTOiaCUy?*w0NFNoB_e^Z!${!&Y=y-~7|y6r)K)YYYc z^)kCyul@9}pIbaR)p~l;oV|Fy;`xw%@AieLzWmUQTe*k-x!y;|W2g>yo$+b8iT zEK)x1YB7tG3ePw`-Z-YXsqGJz-k~dm8xlHWmaY52URHGOEd>28TaL$Rr#tl=h7EjH z`>>Xi*Zj2%acFpo&WH6Ww^@TL!`waLWl@}yhTW6RAug%oM?1{#YUQg7A8*gQs5mW# z(;JKS3_{n9uTIL<5nHq;E71x0g`AuCdxy`xxvggB$h>1Mk?IEfZJN0Z4ywij<+ak( znwPC^>^~2>q|Zrh$Y_lRS!(!anB{8YnKH*bH6*JJ4tNqu;iVa9kWE~!#Ua@Y-kLPq z%KOYMAEZ|!cI&0Go{tB4^)}e7!)B{UN$Eje?1bExTuN;BvxV1JJC2`LlX+C^9n%9t z1$2`2%bP-*xx>*i5iY4r62iR^`(rXK7e37Mt#85NL2xGNV^Gn|r1Omep=XElTtP{%CV~l}fWm05lcL7N4 z+m3+b;2#in%Qwmm`=1e!j5s}fe}trIcNSuIqai0^(2#h35^{`+SEt!%X1I}H>W{Lj z=Hdo#g-YL`hbqvq-9I?A(F)z(Ylr#Rj=JZW*L~}B#rt3bt3|QF@J_D}CS_7WOvpf` zqQR{_GAi%*(C;%O#N_ zBCnBfhDa}9Qy**ln)be1DIo`i9qy$e8Ie_cSMjrKz-o|$ga76lXCexa{3;e@QX0Ci zyHieh=J(Tf!%}R?&=-#=CCo&Ks+PfaNoqCCoAuDd0`2l0I7FrGaJsHgh+!8s?~3$` zr4cX3r@5)X*eqiCpFMP@<0Z%KGM<^a(Iz)rkq>F zb-PJ>5yt_CzJ+|fCz8#_Xo5{cUkr?_*cmn)>SQ$twQnVhm_@s->rI#LO!O1AzVbLm zMN4w)q(%M$;n6EAT5&M7#Ubykf|~U)DWORjQ$&h)XlFc~jX>B#XqGai>bFWVv34og zIL`&yJU*2H+Mzoy*vm%pH5ZF+Sz62p8>N53$Zcdu9+Wh7c%{EU@Ae6KrqBA5N~|&G z07pJ~jZpYldnRGS7n90e*aMdbD95Mef zap+Gg6C5mPqLDy+UJl(@PRn&Zm>JZ{~C$CtRs=;nAm`oUct0~bB}6y+0B zN7x>-E}85G6UcO9VjsL^0u%#JC|O`ZlLUsFyaZ1nDR3CdR%wjk)EJvBSn6UM~gljawa(E>Xap1wU@}-)%#Z+Ha%75kfMTr$@tJqG#%e$<431Ro+x+k`b13IhT zeMTwV5bf8+dgL<#t$L5|#c(wITnVBEf@l;mW_wr{yj$>osVk}a!|$`ZA7q?mNlBWf`86j`>T_gIkd4&E8 zoZ9WwjktCAcHP0~-BYDI**#cVNH%*@Qp%u~ zZ=d^4_v?@DzxPu^OJmilT$vGb&diLAfEP3}L@CT-Z#p0!4aEpx(7!`rv=sr@AlH^1 zh6>3n-RS!{u}d;gi70B7{MxB>ziNZD6MR?o#jK;X_$2y4g`T+@XS&o_x{!#KVe%5} zCgkzJtL&$BQA?%iTF(_>MfY;B)zo=17ax^H0``wOn-16@+d<;_%P=gTfxxnn*lD+OLh&= zZ$x5J_@*(>Q~dy*)+{U|^0DTa)v?=Y!~SLJn)tB@gB3$ASIOiN{0G_#i!l>UQx6!5 zq|43?eCFCZtk1#OPX>#(WWKZY9s=6g6_n`Yj@?H_F}W{i+V95>7%&F#j%5bxGDcK; z_b#9vg)_`Sm5Hz_i^&P}Mqwz+BdDKJ!9fEdWf)H)6;d#f{j;>zmS$4}epV;5>>DmH zNE&4oCZ!x@8>jnsvfdTHqN z^LrzMDxW^ryVaOpiKf-&=N(gue7ODqr!KPN7EM-h#~#i~<1s;Y=$0T{HRY4#J@A6Kti2RbPq2bOq(N8|IbrRq*8FvvPx1#t&I@MoZKyscfT6=o7jFm_%ff z?G&MBS7Ks3mXZqi;KwNj(F%*(fs1IFYR|~8tx4%vII_?r)UKM2C@TB)$@5r%Pv5*& zP&WH8`)&6#&mX8q{lrzriWE;{;(Iq z-BJWs8O|QrP3DLUfeMJkY+U{#f}5!{3>qS{CtNm8Z8P!pMF>2bO zT-U@y6-N@}^vOK5EC2_QDJn&>%~71^Cu6CDUkV$+)O%RQieFqYKQ^P8^*$-@%NCS%&AQi{35bxbiHN(o<8OpeTgNVl+LtV!b2};-IzmC)a{7a4JMseQ zx^|nvJI!iz9y%w}m6o{iMU+aYd1_NI1S03TW&!$hino412gW|~7@3L&-w|5^p-I3< zijjEvUm<5SDx4q#iYa{lj4`io2lVz!>y#o|3?!k%Bsc^;mxbfRN2g}Q zWH?yNFz4kfJj%A;SEALTZ;Cyjfq6FkAp^o`$9l1hQbTCLDu7#JI zJ)&*WJ3BCBH@uV9WqLY3Td$!mw^B4a&jwbinstnK2nk~ztAsM9Fmpiva5{5Szt#F7 zU64Y|H;m&xgrmW(d~2~!PO7l$xSwoW|AO?y?PzSeQac!0%(;fn{+zd~*w5}*l$D~i zjKT^t=C+FWP@3dTjL{1fF$GW6jGJiARj!=tk2Jj4=k4t?Dr!6ozU>(xM%U(~FWxgz zvscK|%GXSg)R{J8{UDpI(~>wULn<+EJ2@}IJc5h+hrIf>J?Pmme?ipt?=k=R*bEx z;WAsE&(BLr124Z;dR&G2GeA1YSFD+kd~{r<-6oMJ*JQoXhiPcnd%;9e~91@cI2|z2$KBAgWXn*?HDx z1;OTL$s}J1!s}DJ>v2?1#@ytA%V{rpSuAx}8GjH&BFksNuPOaW$IX-+{O+a5D)|!H zc22<}&+3YeIIH!yjVD1h)(|Y|QG;*HfulZI+5TKs8t%c!Ke7)wAao?)Ml+Nab3|{1 zFbnLz`$(7jWqKP6_~C-4JEcS19txt6^JCzc6e!)l9-)W%wGIjf_#ypZ4`ikF)4`l> zuV##2F_Qt$1}!?iZN**bEW5Yx`T#7nZk*gME6tHY2e=j;t6Ht> zw0xfBzdLrRSeC6=i-}&&>!;R|0~uSSCptmJygRn35M}GuYi6V?orw6RLIi1n^=mvv zt#XB22Mwv+y6`bshUQ7nJ7K4|j?i zq8iSz2Ps4pOrfRM8tS_TUQL|YaF&q>6qz6Du1>rz`1gJWyyTD6@C3s+}ELLTF zbZxC!tCx|{P#kP+A+5V`Lv0pqLHZ=XPONOSjrOT zSif%Xrg71wu(sHA6;2vo5F`PLCwy7Y{-v$t9BF(Ja86Fq+_qNyeN34g_Ql@&ReYF} zi2sWElPY;E(a$!j`K)+7E_xw^H*n?SL;T0ws@a-PIAA;M{k=hfBl3N^cetUkCouhG zFkF2J@pUULgQIQrM7iC17)+GKEFi*#)6kVcIkuWT_$ryCkDzY|?D4#Lc}iVxZh5Q+ zl`+_RZlJlkT#{gi;8S78Tm&Z}c2td2WXGf@zAUN;~o{( zvr6&v8)8bIB2u+@*}|o##=vEy`J3U%Y>FY)rqY-5s&)JWHR;+!C49Awv0P&)>6*hx zcEx%n6wm<3V_;o)|8DjZgjKr2RKnNf$xicFGuWlz#Te6 z8+elOS|7FRKrkmD*kj^9;ALiR?D)~}@~M*aeW@XuiG$0`Pp55d{A`!w={SIEPWyVP zpbPYKfQtO((b2`|(rD3k>v~><$5PHwc*!C!VkGt|+CXtAU+CqIuCOaIoefQ@2h)+S zX9_C1iB0^(410~Oen187MC}SUL5>j);gC0N@(thp@RR+c@7pE{0#n-zNW+kFI##Zl z1tBr!-l}080cjKTICLN{F=N8ab-PJ6&9!R!QE4e2t3Zw#+vT1>S(O#~-RCs-w+I>Q z&Ke2@UfA8=_1rv+G-Cg)==obZr$3_SkHq;G(eoz<6y5)j==m!-maUV4lL-O+KXx(X zfjOxDzP<3bv*!PcqUUdCx&L#~!^ptO`u9zYbaf5el@T=W#j51NlU%n6R|*4=_Ff@8QM$6=%g^ z*D_yfEE1z8a+E7=87q%rEGwYrNZ;?+g+c1Asy>6mdbD~~P@R5?AMiasaU6W9q0c-3 zwEpg!E3U-huhF_GQrkNN6EYl38@WT)G*MI%{g?;V=Qz+!5TePV)9&u8A|1rWZrL8L z#*Lal9+oYAWllS{%Yy}7w^dWQX@WbZ_HqNP5;WNwcjc=OeDhRN%YK(3QSbLv>pQU~ z5R@vl(yqs`J`s`dHX$NXhE~;?aJFamSqRY|s zYnH7YA%-r8VV4xQZ#1V&I=I~{>c>YFDY`#P#?UH~RzUs8NApB4{nn-VVO!Q1K5$mV zO-DwqNpX>Qd$|Xxk)w+Iv%>7+GaiY5(ce< z!?2l^fjSMxPM>Vgf;@t_94JkmzL%F) zGxI?taE~O*%)s9<{$YRf2>Mi*{D?XQJJQsNh3qlH*v-5&5-~a2dgEiQ4e2oT!&>|l zTSt!%u|Tx{M_z(G0a&qWFR8HY>;UfR-g$~G(r@Zu!t&cIG~DJb$USyZkXM` z#%LFgpo;=!<-7A*%Rf0cnJtw1utQi7Rc*Nrz6B9&Z|#W7bJn;~egxk{w15qjDIu4R z&4<|6{h)!{t2P^+wK*{Fj9CG$qDiBp5<_Y z0)++%Jtj&9-(A!De9(ex^Qff&^s%dU>;59IsopFEI8#o}VrAzP-M)C+Q@UQQ(V*Gq zoxL4pM9Lx~A6zxUA~-Bsiac?95L?y!Ip~Dd0Lm8PgjG+<63Pn;hj% z&0mR6NB2~j+M=515E)qlNc+taEtM8oW*c(eGgo^0y5q@%?=nCej72p1+Qwp;N252( z`VxgEDrZzl&e>!hC%&MCJEm2-oLdx)G*AuBk0VJAT#Foc13xcdM%xzQLR|3kVFOZKyI3J@KRD!b&P-rwf<}&mnY) z|A3E(YIZ1()C#!vhlkfeJzw?`lcKuul(gS?n|(qNk=40HE*6=8oZs{_rV24 zLo#UWQ3|+YKA9IZsW%DMT7pDGp83TG3TCdO@@oqH`EsJ^CB1OSs}A5qJ6a(mI4KJ} zAzN@+HVA05?(3nSdU2rbr@`KUcr4ytL#WCgO(>yP?i-#<8!VrR`mD_NQr@mpzCYf1 z`g4+=j~m9#TSN(L4MheiCu;y|yrc7CE+VU{4_cm=_1!uI6aKa{(g+ffgeTcBgzo7B zbt1JiD6_17^pMb?>)L~Y{oBx)nkQdq;Iz^GFEV-|B{JOpxt44VrtlCaa>%+4sEaYc5W znt;gdObZXp&)YvN4tpt@y_~m0)s`t3y!^Q?teMeY3~G&JHl0t79aNaFWiPEv_Wh1u z8G^_{Fl2X>geCLbtu6EpDu4T91=rajEpuSdz}o#O+s<+DqNN=&lc4H2@59EWn(eV` z^(8?^rhl&Mfny1!`$g@>kgLUF!=E@G2!@ zZq;KVSUW^Gpq?qsdFY?9@G8$F~9ONmC@I1@15TGPAG2JxN%S z%_;B2#P8x;=La`$NOH}5q{vap&zNOlZ;R`m^wqG-0#B-#p0;;WzStZ>e(vBRf4UDWAr}PSn7r|_gQVu}T^71nh}6>YVB?9>!cM9fJ`gHE!sN)Y8ltQ&;eE-rO0y%|0=17!p)ZA9fJdrvJ7zV6{@o(B_4q zyQhFxZ-8vlQ_a`7r6MV}#`$7&85LH>9I?&qx?lRI0t`Bnm2u4$8lKaj&-*H~T2|L; zGG*j=xlU77s<%<+iv{ngTGYzG%Q~Cbb+gzp;u(QvN)4b^?jiDREJ~cXx#0ECK0M0tp zYhu){Lm_tRl}&cWsM3lX^8@qtK2d8|6FrG5y6g1{z%$HQFV>p=)W@alWL%uPXQuMo zmixu@^h)XEgp8eYeJ@1J&Rfsf`sql$jF!7rS9#7}1#b@u)@) zn;V&zSq>s=d3g?ZDb9a+(@~uAXoB8Famus9a;(|Yl@{)h=B-yhB2fmc47a5M)0|3^ zr^y&BsRjuI3VP_MfDjIuff6vELG2s2_sdwV8?L*MSq}crf&!l!0iIp}`>;K7E!*^B zXlya7hALyitts5mLEt)-6k!VPuq4pH*g@|AVZ2~#UdEF@J^^msF zX*lGEsB6tJtK1eTt|oc%FB%oWrgQel#I;Yi4~(MyLnTKTf8 zcZB2VE{XVHodz$jF0{GS1cIlNH*yz5Q|IrIj%KPudN*!KvN$ZXsS<<@* znf*nNNm6!^MUB)v3R;Y%nr><;tbxBs5LKcHdgAV>$7D|}{Sr#>hf1a4?BiR$B10Qt z#VMx}sSws#l7eV}kh1O@G7`l(H64!^dT-0YG!Xl#2ost9aw&~d=C7+j;IS{3vqKh7 zfIyDH)V3p?&KC+M!55<#M5@R;tcE_&XZNCV_mt@D`Uw@y8k!^bQaRm`H~Gdp1Djtp z_A4utXmBKx;ya4kIVn>jD`lvmZ$TA9Mw7DRYEHi}RC%iRX8fEBOI?evC`ls55|){b zGK-3e<$wukiFV*6(e7b>@$CaB!d34>_e<2m}zH(`81(D7lvMa86?$ zLqV}W>dlJR%o3U?VIH4^QVA~Cern0}Jt(^Pnj5Km3=xm&^pTd10&ky96kosw-1h(# ztHd{`TsCmvN&q&$kjDc;pqdr;*_7(5T&rQwh=UOPGc2R(60jMYCwc8;W>u9z4 zjjQ}eXTky`U=5v|on3|li0`TKXfPP*&HBp*@5Gs-qlRE}k;($rQHV@2mVQ0e^vrIVrqsg9t0pmzLx`i&=##ghJJQ$HIh{qTPj?YljI$o<|v zpQk`?JB2cPc0DA!?vC9~-5@hkIFkma?TLm*c*3weCp*P79#<|r8SyR9tbI?R#(b(9 zBD%%`iIndd4q4yg+D}S##F1jYueiXknW|0+#R7ksdW~};!MpWQSTmO_AgWp_O*%V% zOS@|xL`<;sHNtJq=JyJE631YnT&{omU@E0h3@<)*G5e`Fiv~qTQ={ms|4#o!X4crP zG!hDpD4OB$+_@msFm9!}Q z%78!sYNklES8__pM>l@k^!0I z_c-ci1O?^;g3bOQE)&Qkwjv*R&ta1s(8k;*rds6T0fYBDCFHM|RpqACVpwY;JBv2>Td4<=~}> zRP}2N42vNv=-AmJ3sLHYnFk31;uS-~S|wcdDA zTY~I@beR=a$a6-*$u34+TiE64irXY$-CC)Pjx!idL1AI|cb(VPjrs!2Ilem_TQ8ph z&)@V(-px>}L7)s|DE6w8tXQ?9Rx@zm(1O#}6k|M;yAj>5$L#D#_NY6A!1ZRIP5mnQ zmU~C}q(tJgmW8dY_=$~Cy=p0hp3_fsvNtGcDs8j_n#0?=6T;*10;IbuFlqbKtpih_ zMk?A~NxWN}Y`>#wEJAUn?ls!L%z?2Fo4M4PCdsro02;|}XDuHsiySNOBW3{Uqe{Lj zFYmf~TAkbHm7nV7mOV+u)xSy?Jgr|v9!6#rbgI-cG7C&>r|0GKoM?EN4iq2QO4bb< z*N+OJC-RbtSPugmJ(X(+)$*FtdSAsaHpJcp;*~DygME^St?->rr!V|dPs$5c+pOIh zQ_7WpobTZol`W1bP5{Ugjq6zALKa{Y9qgVNZ%f%uGf=@3(7_W>!G})vFE^`BDi69$ zw$r+(z2$oo6GQ3Z2=k?lmF8AhzwD$KIbPbu7|(4-mpq*Nh;hLJ);JL`JBd87I(;5mRjrm0GA7&NS2n5bDQxW`}r zf!48I^?64w0zIs#eRG2Kt=JY{LXx!YU?EqoBdx)3lx65MYIb2pSxt)z)zK3doW zHsvBdrE?>?q`5+VPzap}Me9oBfBRPJ2v8m(%@Z)$74A}7?jZfC&N+?o3#I4^Iq74u z)E1blLj$AIv9_o9Y5h==puh(cb_%1d9(GMns+` zJbY!)8yqT4QTDq=q;>+uV7io}9xNt`+;GY)z8C?seM1fY_WeV;u#~=a7g7X z-8WyJhA$_J>5!kbCrP5Aq}LD0W`cF7YA*55l{5r}6)`bTSPKqvNyhnUrMXqC6t!&= z20nyBlNykGS-&7wBFbYBgMT~2e3N`zS5NKY1JvCQ?m``CzR3Y|)xt9v)&ASL@&6si z@%viwU*^L9lW`mz|BX0~Kll8vOhx~y;PHQz?qDQfvgg>HIoSXlYHPO5|Jc z{@|FW?Rxa{#oJ=|6Nkr&FoKK`MczK*d~0L;b{0OWNsc9@b;-4Fs#5-S{g;e1$+xzf z7}?o5#kvCl1x3e*H|3R}C?^~;v7&2KGF2^>ft2;)y{}k1`Q2v6J6)++dHLi{7S^&7 z=Jh2OLgU1cj5zdL0>KZ1S_iRuygvDyGDr5m1`%xV4zJ~IwpMxYabH>6U^{&9xG=~H zWh15=Ms_}?RLFsOi$0jNR8q;wi#ki1BpzQ)*u?qjXe1}-H24lv`zfS*n@9Ci-wScw zMshYazcTt-U*A)KBW&|K?omMt*945zKNzK06g@K2&M7X^(o~I~9vvMvLlkUqWy(Tj#4l$Hx5}Rq zxl?B^-qOfrR(!jT9>U$xeid5m`4O#cslou!8BFWO4k_9n1$D& z{5qUV_v|$@vCqTg2Y%s#3#boi3TtNmlnjr?9>>~juP;#d6v1Ucs zu^h)}I9TjT=Fn6D>0`6e=Wq`U;w+Wo5APH6AxqW^a-Tn=S*-;`7>R?7gd4Kao~&12 z1fUC`6F~7OwNsjQT#fjhFTwHV=9vy?mtZYrbPKvngm_HaTLiZxdRnQ1IvY(E zv1+e|&foUr^SFNy-fVS`o;rx${#kJh`L$}Ui>+T&{v+<-?OLaRMoh)7ho_ty6?*rW zq(l$G3Gz)UM!eshBH}mG**n>0vt>N;Um0!`W3x2ONhvz$-q;IY*Ze8P#diF)yK`Q^_E1``p)3nOXwOe3q_ zMA#g>((b-xTt#Wg0XZ2E#h$X9Qt)JpF-qD`@6fI9KwOmeW0i11Hk~twDaqEr&e6_} zxnqdRd9MWZ7ea4LQKA8j`_D5a+AR#>>dry0u;=H1tZ&L|bh7Ica>9pGmI%O6OtNKSW+#wy;?e6I8m6LUxm)CybGRTvIgssih|Jf9(-rJ? z^VVRM`O0Mx^*;FJ3EPAjIg`Q3LSRApC3ufC)Rvs#C3b7eVfx(GEcC&ei2|)Lw?Efs z(Or5`w1{H~E{Oh)O1(P^R6*4kr-lFevs4QWyMwA4;RWH7Qy&2rO;_W5D^rW@ZOa>e zwq9QJ1mAA#CF#X0g~!iKyI+@Z{aLx^zzyc}ZiG+&7LEVD!Tew4%myBib1^qEQ4|yW zFS2GcGcf;0)@()wdRCTyo{9TY$mrjt&1Pfy7c~2|B4_s5_3iz#<-A~UV(EweF)b`1 ztQHj1N5dugWuAvA{silbC^vJjAwd9x+mf$O4%GL)*r#oxV3;tNY5u9CsuDOM+Q4P{ z@~&n`rW;Rn1bV7OT8xP&z9y<-t|@PyH+iXs4*^jC#12k z+Lm8E#>Wf7;Q=EfTzUzdGuX9$a) zi3=UhhSg~|SEEth=2DwdMw16B(x0DdF=9qq8l*DdKtSA1oDQrD74fkh-OpuC=Gk<; zWxLn~2*u1_Ryw&>&<;dfpakJTK-9#d`8(eZ?p>=g#?>DkRq!<*eT*jrC+z26CnQrm zrc7Dm>aRkWh@hgWx6jvaVV~W0-Scul-I~q9ls3EiNWwTSeS+{ zt)$4^m_CF^bxhw4>ek2K=JRaLSmSU=0hlJ7WkpWE&c2X1Gw7Ak z`Gqv@d+IjpVAz+-SvTHlE_>AG$wfwkg78~02Why#tDJ9OZ(kggj**(an^WyFTbx-) znxxIs%qOswYL%7x$W^p@Cr_`n9`BvLYF=CSTxCwBrbou4FWQ_X!XTGP+C z>=1hoG29qzD8Jt--I|dlF^-SLdA%z|-d($DG08kZm5{D*DHhe%mDUYc6OttdwgEV* z1i$AyJ3nSwn3@+6?<#YNIot^N-e)yV8h^-%YAx6c)i#hgx~?pOn`QTSxm%=sx_^@HTn!4 zg}~&{JEHT+YDwgYIqs8x^;cNfy}=zm>TKPNr-k8&D19Eg+w&`7`#sbQjtf6dCU`nJ z>y}cRILUU?BU**wIC@qf{L}UQizXj+Id^Zg;+Q;!%$3=a6boZ&ue?XxJI^bbVu8c( z%W0BSN2&mj7AMdrr}hcgfi|_$A}F1}91MTD8;9LO{Yfjt1 zx8Jg_CZl@jiB$ST$89rrmvy7#RxU>er6W)(LB|1Eipes$kTwCu0Rqx5Ej9!VDAzQ? z#x2=tr`g2_NZ%>FPS9=6?c%Y8btm6F^pcWG<(lQ%aCh+!Ym9c4x19jGm-&53ri&G! z+$-sUkD1(%IS#wjk-m<618(Kb`rV6?k5HSey*~~J2%;8f5-8BmwJAJeD>>-UrTJu7 zOs9Z;Us)UJ&OmItN%t#jcNbJB*H-@Dy;H_7fBxsLbqiD7Q4NDto`YGT%wv zYu|SDy|zcl|I>d$?p(wi-lfp>ou6i8n@Yl8eK(*d2LI!kdlluwSf~z9xG2pa|7@Xw ztJ-abcqpQS?-8XV@aQQLylCHle4&7Nw;lsTOK!CkpBLNXJ0y6$HOLp_zuE&LP4d@sK$6A(8ZQv~n7@YigFexJylJ=a_FtCr zEu{ai_JW{<{QnOuA^G3vL(p6^g=t(oyqRdTL=Z&Wdmj&!RMK%|kS{YgH#eh6bR|Mg z0fIfX)W?WA^sz#9s5#5KBO@@*AkorVT3WXr8JxmJoO^3)I>!X_)D*tTbtJSO#i?(H ze!1g02Up6IQ`6Ea1|4D!BgM}bgMKqERi+Hz4VKSfv{$IsPy{OhNN7uEVz>ZCl1Ey| zPSqmIfPgT@iea9TvO0U9Tfwk7$hBdWU(wF=FrIsmUQ;I2*r+y&&b|{#79dBB5h-iG zZ2BRXB@!(xEU3rDac@OmkJMCR9knm=z+DfFPGarHI?mnVbM7X)UO$VyMy*Zl@B=Iz z$W3^l2ZC;bQd6oHE9&2(mc~kV-X3JGGk_dD3wcwN0$|efnfK_}8Pp;q+O^=zaKLTM6Q$0#LhtllRMTG6=lfP8w;<{i;M(DEk3iRQ2JvIGMyTAWiJ@# z;EC(@(^G4pMRe$@jmLfvMOwjj7Ek^MBEBY-0F_$n#)I@ucc*2e>e4$!uTsTSvSM?1zR9ABfmu}c;` zgpU#ruTSqU>{$K-cMWiyk={aCyR6bkqC5xrb<|<&!u}q*wCG`Tgq&y&iAhQ3i9{p6 zyH}i;Bg0nF{vgXE_n`cK4oTcS)pjD;Ur^RlAp)NXxaSVTv1L5}RP9*8 z-m|{39Am^H2Ke0^Ej_&=Hl&)SrUQ0(=U~}@bio|{I@BH~6(SLhxY?+UK8QiCN>06k zm&a6RK6>`|9hZn*r~n+EMyC8QA=$jvmUza9_=J18r^n8=%uf2ls*No%elH-LqC z-7+T6?hT)8U3up9n0G4dxcet~4pSqgyiCWLcTC==L*l|RVJj=E>Ru)PP&P+LM}Hh7 z%ikSA2;{XvCjG-8$77S1>%!RAx}7A3c5%1EfI;H) z-!H4|xPwQYD^ISTD1w{I#m%k!$EgxUaghtDcGF#KM&K8$xbfS&9)=t{5v-fx&-HAa zo5#mTPdsW1HlX@ih&f8SUJ4qBOq}alJT0fr%-@YquM?BtYQ7Yu#HXe$TtDS=sc~hw zWC`UR^O~QbAXppWd$pFn+rKb*%xF)~brg6d)9mH}+fw4+M_dOr&oWB~%PJKLg!GgL zp>VkM8SrpWVh%-^fZpwGBIn@97#x97Y-fILM28C(YinyD;tD#C_lr<8S}TDeWs2e= zV))~<>xA!$Q=r1Y!omVgS=0ecBe9{jRuC721Z71%zq&0HfF*Q{6xa+!P-C;&+`}U; zT%v4v=@$$vca_FwJ3}o}Za(*cpRuBH5CewAj8HQ z=)W;mO_3TM$WxT-K(>kP5J6=*1|djM9?D@u$`O=p(f;k)(Q)GdAf|7b&3!OZUKuXn z9d4FY`_f|*IS-=Y&}2ziQ1JKY+RpMfmk^p?{m80mB6jkt7kb1$~OZ!y5E z)RM8RK5?92(iMf`+<(gcHoZ}G(bVJ-+rAvUfcV;wkZngqsxWsR?odD{}r?zXM z33Do=-}3nY=el2~!=!?*&5XZbYi~A(0qgaYWz^mI3?V=$5>J!C=7^!VaR>AncGgU9 z`VgGszWl{@obH$3j#4{Kfno>{iVobzV8so#YEaSfjMCTL9yy3J?o;iBzwD;V5dMRt z-ybsuV(N?o5uCU83&)(i-&f60;W?^sPBag9wJhFGJj8hTe!AX`(=)m_=hs~gx);)N zN{FXsW&%jW{Ew4pMstC~Ggo1Q$1H_ZDpOfrE)N+VkeLb%j6-hPz|hh%j7XeCYMW@F z05~NFYUSM9*8tck7465K&(3=l?-T<+`~=mAci}h^!5KOifsh zztvpqh`ANbbjPHNIy+L#YesUFGeqq=Aqa&uKa}6VCh1-KDFBT=AO>d%Ac16-7~GZv z>~zPFT835ad3s9+-+KB$77ntr3GT-wf{V=pQF!;_XJSZMX zAe9G?83tQa#t9+m8zEKadg`NBJ?`nhrjm22{5CASp@UYA(|N(3#7k9Jw%%A#K_luQ zd@)45@|V;y)E3opE7t|uv$T)}Lc^OA)3tHe0=qSEUT5B??GQ-|C7%eS9g1993LCALqJuaOaL+s(1pTxp$thNcbJdSukO*C|NmPY&;d{J(ue+B zCDang1X7%uE{HWBkMXR;;7IHj4fJT1Ygp zNB|Dd5{uo0>f#k=ezz+%E6cQ15~y4Ny8J-8mR19v2!P>_Eh*ymKtb~K^!z7^fQmCV zMoTHYGHMNp6wg^>LX0c=Tf{9{C31p@7XlgiH~mm}W{Tko)5jA3nEm~1#i+4WP?2J9 zcYFJoKW>wa76H8bi>O0B@Sfkk0QLJ_m&V56fbRA8ZUed(NUXW5Yf=mj6411lmzQ&) z6vtzKbIwm4(gJ15nl?!=Vh&%-;SbTqdk!hU+cFQVZEcl+!|!Jd?CSY1_jh-{+tBKG z@OwmobsvF3zW6uSjE#>2r%j5XhsxUd8o)WvXzihlaIx4v&@_P9OlS&hERYBqh8n-fRZW;V}@4!*a(&p(a?>;6SQK;>#fYvRPDwBTxU%gzf9tnvutE}-lZ zvn3J?NZ;EtNiF!@_54J0E)Eobc*8I-l&cJDwmHF3kL~@wf4l)@g!I-wJ+hC*BGbAA zrP&gnd0R0yiuWn_KQZZVBvTXs+Vc)`?~UKc0ZWF{`ZzXq6( ztv9^$D2^#0uyO&l$4Ou?VxoopY$LW$%5FS)b!4X7e#}&(4&<-QiE~zMS9t^p=43kw1`vjNQ-%+ z&H_+1iH*)TMIR(kQ3u(mvI#X0-QyXpcDhwTJZea6>lur3La{YdLoVLc`$Zb(t!-t! z_Kpso!ZO+3a1}!#*~Rz>VEG8k%l3;P1bk$NZ;hRGtoS}Jm;HKf8-&y)x|6l#KO=XY zXk?)KU7T}w*f+eNt#5XUzjy^yYRXralrHw$)-A8Copv0bELMf#v}gag?tO+gAl*uY zzfq}L^gN)8tyUFS+Z}X0@VPluuo83duzj=F%>g=;8f{V>aBw`XzY40F-R!%Uh`2_g zPnM}xw6e{Np5cL4qR-bgy_54kZ2Ik5aoliMd2JoT_L!M!sHQhD6?0`ii8Rr1Paxc` ztgQSnRM?d-HPA~aODyo{xZwPhV22!gHfIuOTA+fIPurgVo)?EtniD(xp^tyNF+mp!qT~k+tk84*`6B#>Q^lmf?b^q(j^<z#fB8D8PmoG zUV5Q9KzxvjcAzAyv?(9?qC$_e7^wW$Jrmn}Z~uq6w~mT33j0M-R743WsR3o^?ifB-iX&6dc>F!Pi zq(izvdg$&F7`nURzTo$r@0_!~bMHU*u60>UTuW!>oxS(-KF=@qyPv~w=KEdjSH2w` z9a%c3TrpDQ4!hyRd{Q&MCgmE3yP~w3eT=*{zbH+<^L?w%R>~tYMC`4}(_#zHP?|C# zU6l%fBm7BVlA`+s=tgvO3jP~jigan)qUr<>audxGkn91PankG69|hpM-e&_lh-yi7 zPjo-eaDVjNiRVd-PufWY8tk?=3oDx7-4j;s?B)N>k4{XwJ5ImH^E*5q6rkK~^{(75 zLnl%LDyZWyzs-1me}5=Z*0{WxwHA4mhm}$l=A|in>n6L*;;&fJoNQc4wL2G1Sm#!8jl5$+HsfQZ3kPU$44@e{0VlMi0+V z@al)kObMZBUoirF!eKi=s}(sU$qrb|JpZnQ!Dl+L5t+n^!5tZYRVg{(xh$B_XTh6X za(#>`5s2D*jNk!eN+zWNeDRWMfOf$!1YwcDZ{BPvE==4KlqG@IJymn&O%YpsdJ zL9E#YSxh?QS~BEoxN@*347a$42TQ`hMR#XrfHa8i>9VqMN)ro!4zS9{x%qjVhAp3P zxZB<3x@7%qffnqbv-1;My?AB`oQcY!UB}?V)~7rmn21|Wa(UR2@NE@ zJ$_9IM^L;2FW0h|jQQAcS4E~=Sd*BLQ7U@T!yhCL9xkJ6DezcNbz1fuU-{kCRGhS$et)z6c(Jfw z9S_0%A;E1>l#`A?X&TWhNPDc*l_`%BjfDkt91s<}-}skEFCuxpH4z{%!G2 z7|aOst}~3aF}x?{0|v+cq}m?gupKcbM(F47-@hODS2#kx1_cv5#M>+y=*av4Av-)} z2ULG@8!czVT^QzB* zQ4Q?Td}|IEJ@iQdT1h7ee0Yed2h3OY7*p86q7F;xo_Ee83~nHju3_LBKA?ZE2lbY{ z1VRC(*jWBol{G55;x({#-;0R;GG@%A%Dh!@T+KQ z8UW$}s0J<0PqGUDHfu}%mKY0)a0h+}m*r;P8z4zdKZJnW)n?9PY=Oop%BL+J!}&H1nI zZ}&Y*nm!h>t&xU$JrkCzC%St_fAP_`^Q$fwkUIf2?H)*HFHJKo(Ld-2vM6r00Fup z4Lmo;cl&ww)V`#>FFl)w+5;FbDnNBk#Gq?oO8HhjC} zyf88G*5OSHFtY$=$v090ra6l^u@)&v;r6Jt^{GR^-fC|=Aj_3LGFqT|iN0Af9TW7i zoW=fbjEsN*NH_r009Y@;_kgdN^ee#E*SGn0*ZLustJ2`S6$nt!VZAN;4-*LBh`cP) z)Ng|eyD?glK!Sz;#Tsd7tpL`Dgt1c`l`#WfSRj5tESy$ze;@6I&d0pJcW_{1WhHkj zO`V}^Yinuw$YK8%)(Ff2K!gDT74{%GjNV?K0|5u*So!`3Gr$_QprmrZ5G(a4R@B=0 z1I%vAIWdA%=utKi3VV=E5XhokhB7%ZfWSI_3f?;924eJqvVCAFJy4hWKZm9TNqh!@ zVX1nSMv(q%$Tu=p6yei>M_EH(e1dFgTtFovmB2T3tZ&i zjQ%tIfNX3U2S^`=d3fL20S*sT^{TBvX##Q?;VWS%HN}Rc?Ox4xjt!Ysi(dl?nf_ctWqMHTU4mqp-cQ zHkgz+R~O5|J$QTqo7J|w{bNCKE^ODzz;!<-P#A+Rb5jJgG@WwGrKUFTu2+RXmw(>cE&G8Z zYtcIGn1tcV@d&b+iTx0BFlT3-m6Ey=4y`cSpY%dz5ny#&&81rkCrIr7fm8TPaav#8 zVY+4Z=FP}(^Y(diBIUKmJEDdh6SA$o9}xx{)K#40p0_G|(}Ov)NW8^+7sI`P+qO1X z1#O*ne&MaQNxuHWb|!aMpgZAV{}~rg*?>@G`q5nv`J>+XjMTVgb|%N3_b-=s*rJw? zwWG=t)w#nqX$2pf)V6or7b(#XXaZ0N$BtPV0|Q(dn`&wRkx!BC?SlmNZ2|}S!rsxt zlP|VZ@8nJ%FjC4Vlf7{S=cZ4tWIt~9jiTUP32O<9aSK+W6DK`A78v7ArZC^Qu#MxK zX?ZWfud}~tt^mWI>)1vl0Cv6IOrM!lGOmYuH0qUYaX~MR+MLVWrM$!JpnKcvxIZ%o z_$Hxp1SvL;LYh?2E6Bg(s4$&u92oasR$$J!#(o}Y#1Y$K3Nx}VsJVLlhG~fZs~QZM zvfxa<^7=eU4vlX{e2;?)ZogW+l7GE;r%~Oe)#aaN|1KXQHA*mOHW=>!(r9khnd2uh zIk3HIUbt(SH(jc+r zFbt3Zs69PQ<_BL7+}G#;ZV`zI4C@#b14@82pfr=d+$~VKYcg;bo|^gYRtV_EkaRv* zD_f7@Z4Rq!Z)$zw=8x+jeCQXmwkB}X~Ou6fmO$dEuH~MoTK?SdYCIN zaWy}=I;GnH!3>EQ)E;V%WXjeXW@BAQC>pVvZklJ~EcKWFVrN?8k|p|@OZ?q%on zB|-;v18z2Dk^8EN)_{0=F@b%`T?u-h(x7yndMQHLI&aB2Xx7tkWn0_t0| z>b_C^2mi~F(T@52pE=)F9MY+px6&4O92LJ$o;Xi;y@s$zqb&|*tLl7{x|3S5U zS|IHJ3Nx^3fPUEVx%3~DU=t7+1h86{?E@=m(9qT^I4-yY3?yj0?iR+3heW)7 zv_N<}4>-~lvCP08+-SQn=jGysvWavZt{)jI?bDRcHZ$<6Ul8+PLr;c+Y^B2mD~aAs z=_QC=2Z`|)_{Gcniv^ujn+*5fPu#TfbMgCDY;Kx9$p7m`y=8zFo-at?Cs>YM3M_qt zjtd<*;1Ciu%fKMXLM*JcIfIRY$2`C$Q8}X>+@k$c%CuA&y??u4PMtk>J$3ds%1p+A zqS<%wJgugdnl*LNx@lJav$DyeklZh&hsEBCc{E*s;Zb=70Jp^7qAdbIIxbe)_q-d^ zgR&-fyYHX82+vPtb`g?uD%`?+1@XA4+1Ldh1dtEfzKi)3g~uSw$1?ge;D7jhRo>MjC4VQTCEllLV24YV^`n}Ico^Z~r6cvn~^ z8&iK)%S8KHz>reBg-3c&~VGE2%inZ0vrq<*SLfQvi-8VXRW4mq&tAWu>g)kD{@+38+#6Ae(U z?xs1D0-O5|#^yK%RdyfV`M0iQe5s!0DpT{aoK2NOa)hC?Kwb$_Af-GnQ-jUJCCQJU z(_%Cdl`9?>B$Q8h#8Agii{|?UJepEo z9|_?DBu|CL&;c0Es8#i%%QpQKiGX}Me+Ld!wGZ+K4dENKtf}c?)Mw}CB)F zK{rnjq+YW?^3`>9#VEv)4HbdkIH6)IfGqVJ5#dJ)phn<{DR}K7@KCj|$>Ke+LPkJ< z2m-Hx!E>Lo18X6R27I9idR8-N%!i8Qt1IpugzB*%pup{XMnL$rdbHX*#X`H(;*A9S z^~uxo9?-j~fkFX&<`Jvv z(j=;uDod5GG*5iHUI{KS0|V8rvqw$@kw-Yx4uAQBc1eP!k*5M&Fd;d)-u0Ye2LXYK za*Cy(wQBeD)L}{x`F9pg8u#OsgsS=;mqr-A%(LHs$OAX=^n7QP_i8yB21h`U>Rssy zkL*@_su5FNRi%$ao{)`9nhTYNi6VS3ZHd#s$?aBrZU)63d6*F@I5G&U?b3j7rBk0~PYMfUn8Lwm-vPy4RVrp%OlS;&|pv0Sv9O_EVZzERtilmtuK z)Jr`qdTUYl_s5_Ewy6M<-}5c=bEnqXXWpe0-?8MLtGIQ%}B)3@>i?P0;)jC6cV>bH6441b(9zmR^hx(}%RH#ZIW!#~?}T9Ednh5)-=+9D44N55`d>e=q0@t z-rXG_nRNqIl@Gm0W;84GX1v5Bws}SL4L;GxS_(Q@n5?TTv3gq4tK~S6g`uYCd&X`J znoWvCZ;P(uUd&a&%pYOV&Z#_Eh&IIUxzkm-7=-(^ttw@LV2aAoql>ILAw6$QR7GYw z^wR9Y2Wde0cJ_pafT}M}APM?Vy-OT8ayZ;gDy^=QV_EXrOO?yMmQlD%!*>O`ztG5w zP6z%%btA{ky(V4S( ze4IHywJ7}SjRx$_I5DrvUrHr+lN^W59`c&Rkdi=ax}5_+3Ys;9jV#YRt&})(-UoJl z$e^;X_i73KUPtddSMJAa)s1sZUTciQC`;Y8^gPkYmM>j7!p7UrYJFH+BY4I@!5FMX zjETwKOpq4@YmG0bI&7C*`~5noO6@Dy8IzCQQY2)RS2JjiX@sfmBPg<-qn%zFT2BMD zj=>}G%&R^6q4?|<>Lvo2pw|MSb%S7b+t!xZH1}TT6V*@Y3*eG*Gj6>F62#k;clYX_ zx`GK)*V8?9W3{5zbBXp8zt^pf7pO^BE<{2udiCx`aJuuki+R6bvpMzPk35lB?&n;j zlYg2ndilLl>+tLD4121p?2DPu?^odic7uF5J@lJP7RZz}$@rsl^ud2*i}PjG!hCRJ zIkFJH;kPJ7z!FnZ#%d=?$)LI(mqr08H$a&iIV9w?iYZ!o10g?gL|`JNdIL!cAMkyR z`yP6IHv;QU9z)j9??}`B-41^q~P-qJIMznB%pRWGA-={sL~Bzv55crS5y2 z*XPeg@pdtx+`8&KD~37W-=6nQ90FUaM{HSW9nc6wnfUq9A`uaM`<_?Y>Z?pa6)ye& zmQMA8%XTnh(@?_-u*K&J=?`FM)I06R6-|o%Zf+KUK=SOE-E4^{BV{dXPsP!aoKhsN zpg`n(7?zQdiD9Dr_zaNUHPzL>0TqAZYIAcFGbjbD?)X?`vgWM}*cAbo0r+M>l>ua} z?mF%K>y?huB_LfP^mGFvBala1ftmvd@sEi~XCR{<{GLDW3>ybQfz7)4_AK1vgmn6* zt1U9j-Kmm&bAvLX76($Ui8Jc|pgOHx6a50o|BPD`TN$A;75W$oJz^=KhmC0fq zTCFY;sMN+T0z45Tc6do<83#aPB=l~l<7y;Om0EHDN6cY@k-iOsuS33GoosHGG&cb@ zou!_{ti)^9k8?O=P_{)D(r9Ilxg?O`!#hOK5HfwoLWVTfC8$%PTSW%o@T`Hh(4>^I zVXNv>d8W5dMC6bgiN4*i3dyGm&yc$6U_X8@x5Exxl7C@0xgd%VsVroT^r1V%#vu%7 z6ORqd%5#l*)ft%q+L8tqOz^rduI@KjcX)F5cbMX8+#3i&$Xj4clO=lbjZC8UVf@hn z6^1W6PS0ko2mAVREjtH2&dSHfRa57lYYyHVa+gw&^u|UB53HgCd_TT{jv@7ZU(0tfQ2xM1X=T#hS61CMh!w$y( zj2V3~1t10E<3t{Nzq>&IqRNV5eWubJ_@KunM(BI_isd1p6qGc*id4p|rh6KY@({TR z7%^TVVQX4z7?_YjzH^X>oJU0WFyssN6CijJFerTkQ@Xn)Q(b|0USEyZ^Ltof7<>bt zEeHXOgwPj&WeBZ!m--r);R77r)erwt+!%}i&hc45Loj~!JQ36{zP{WM{04GqT0Q#) zGV>x7NMcXE8GZij)fbQ>pB`7V(z7xSptI(~Q0tpLr{>YxNy8t2TY4!S&tS^WofWxw zIp72=wCd@V>*DnSkR_zKT67|hfem``MJoW3PF}pBNQ~u13I$VHN+5lEts&k6Aqv{K z=uhSpxWBRM=aF+MlH$egdhmT8{upgLU;sc>PEPJ_UErSjQ&+4B>)la&GmsB97Hz3O z2p=%$7#ZX3$W_ra(tw?6Kq`tL53eD=WR!_aM|}WE!x>M3hxSq!)ZL!o(Ob+qM#Dw3 zdj8MP^Zp+n^!@+ee-PNsv0JNR)~a(lsWuo*7V3d`OROBDXFjo~>Zv4uWW1A413Rf_%;IFC^hYoI8mL$w}^(0N~?-nMdpVq86bjqdd@!mBva?m%iyPRp3TYb&; z05k?!>3vrbCQLl#o6O zOj!t<&fTo&G2_#9uU9o#NiCcflZR8G2exr@a5<TKuqgl4dWOWD=;`G^Fp8YR>&;%rxx#1#~V;apAv7cHuW+- z*^%qrroR3&b^O9o`U|D=w`Rc*{>4d52Rp_uFPwW{?c?ng$gNZ=yiMisN@{E#&5ty} ztDG1Z9!gB9$<7)?*T`J6&wdxI8JsHU70k3y)+|>_GKdZyghOxE`8 zC{r{2rF?iP^|5ppWtv8R!QpYNnO%98OK+^%_{)2J$9{(%3viBRiT|SY9LITB1K#-M z`Ii&bCeJytn$7!CF zm->nk81%$*KV1<%Gz2dO2JP1(!!W}nkJD~fzS)1Utpw{d_??V`9h{T*xl1+D@$6j2 zgcs)5YhNWahNkjjbZG0IBH~#JUawighvRkuTbG0q3Q9-q@%xb!0)v!(p8j<@rL^1Y z#ywBhr-WCiXRixx6d*8>4qTdHpD0%2AlTu}ca7nU^crH(N$Qf@zKnOb?L3-{BDEpz`xl{M3bz zi;F1h5;^vL&t>w6=V1Th{g9uzM7;AjoD{JP4HDbzgQyyJnO^VTat|ueLcbbFB@^go zP2Ih+*kDgE^|odc(CY9P_(>L;NCn*pl2=vUi5}u6=Az%V+QC}Kd0LG-SlF((LP$md z&00%6k3Eo}UD_?{j12RK4n((nCpUwp5HIF*4M9ZYjIS@+FzSw1r@OAPmV(}6Lxkmy zZ^BSd-a?73HF59s0alp-j(DILfr(cwG>_32E1H$qH;s^7c^~6Lh!TYZ-45EqCZD$ z7{;eK4UbY~E;Lx*MNYB}_lYhQ1l!7zm8LNURi&i>;RVmY zlx%$E0V#s4LBL&a-P&cj?2y>~ahKb=d1~&ay8IHXTeGs)%3GeE0kie&*xnxk`@3pV zCMcA3_R&ETg8D4L{`;8V>iD-1u(w12=uT4@T|{U*&XYIh&QWqD7aIav?_T~R6e)}z zlCl$b8CY4LMnU3-4M9GW#D)B-PM97;g5L8P$GBDhyCybvgXdq(!P805fmfQ}eOg_$q!G{n@HIY*o zNaU2^K0DDBV5)w&A-cvJ$ofZkJE@`267zZ%3$&9v1=g(?9X(--!wwO;jSvJxlVs@y zj!}2ThHRntP!@)krKAGnGT-B3OPa#&$N)SG>af|P3(6kRu)a@xgq6=Y;Kkpjrt9nPRU7?cJZ)(z@Bbxau{wjO? zVh0{19{=oyr-;pS59dYughrO^JvI*Ut)E$kT^}Qe%2H&=L!cHWf*1>#Gwle#{>(KSj&|jLUw|%)BoUZs2)TPp_oQ}69@@xx5t5^`q!=Uyc+y5w1y2Z9$ zyf%)JD{3#fnEcnCs3`tEdapbF$6U+?DY2uORT@!f+4)&DUtd0R2<+z!wR*#HdMTn+TKiIkpwZAYd}YvT6Rc7H99?% zrAwIlA#1X*LojNLmV!j(ggiG@2*luqsDZ7fX_KWbUxGj%U!Yr2Bz!zitcO73b++iw zcmGBS6_r*@%TguB;6lO{et+bp)=k$dKlg9e>9|vDHm7&y6ie;0>f+VA(LF*b-&|C& z*^Q2HlzRiI6x%i^AVmHmKA_xnA&=_#M$lMwC?swEr;`B^B(Y=sudA_JYCi>|#91oR zg|zGm#~u@y@{QU_30IELmZ)4G0ecSXn0mMWjwwe7%AW*Q1aV|6R(GM$Z!nB&0B$VL z6-zP0B&huVd z=a{+<&SiqsG;rvlb1zW1^)Hn3I#9aafc@WL`X{f|f(Q|eE=KsYY8N(|aS@m>e_-Mu zybts|Wz5x-6sRITJ%5TIh7$ln_(pcaIwwKY3vppY&{z2mdx8KPE$2Dk6r^6qJ8x(N z-Wv4*P?rDuAM(z636D~%y|fenQjTA$jdBm1t#^Gq{=CEJGE2MWScR0;%)B(~F{ycL zUM^SS7doEosZ&|!Zp&IATY!7NPL1X2+HB%UVBeLn3p!yxjJeBti$S`9Ih7sHYEGMm%W&-nu>Du>xmgW%0Uq(U2ne~Nr7)81%IRE! z%edw-YuDML4-3EX#-}UEer8s}Huo#cT2MLZ<5kANIn@RnX4Ch&y6}if>%dwL7@+Fz zoU&G8f!En0QHgvIXH$yOSQC*D6r?2pqNjx#j0w4A?58enJ#>(>izeK!(8b7NZ`;f~ zTRyOzY#<;1q!IZjni_KEX!`|l+$iQ9uB-cZz1qL*6_wy_Z9CzD)UY2Yb%oPoLf1R;g>YQAzhA7j8> zr6emLTMV~mcu%7qUZo?fipW~6-*Aj>FBMo+!Ljtz2Y-pQ2ksvA;+6*gar|+ zTz98NjWK{cl-H0X>co>;T6< z$mQLMU6Jm1NXZT;PF}UM;kIGYGC;Ft5D~bXY|KMOt<-FLWu36hq05VCFBikZi0gU- zK!TwaPb1qZz$aVkRwbzVX_%vF~&+i z2Xp*_>27z$-PMQO(_ov^=KWvMF-5|(T@eu0!^+=4`uK3myz3vpB4)L{{AEp$&P7=e zXx+hrLQfmzy}NeouwO`BaFZ8bX;8YZFBev%U4_X48ckileBr#q0&)y-m#U0%X zSSIhG8{ct@{YFzbuo^uFE8I;lOp}BT3oAYGEq5W!t6kh%jZ*L z_s?{fg;Jfz)a^X?aL8HAc& z8@`MbUfkB1`@yLJ>$%etI2)OjKgoD?-);z#2?Lt3g8eaQfc}^?Ek9_RbVMDn`ONIo z-`KHAMz#?j*h=h1ou0GxDs=yUY28M_YT@knzMWhWSpXKRFVndd;+ZHA+=ABY0$pSzG ziH+#tnDK<1;`G$e7vIg@oA^7`xE55E(VRu)TI)7bpOZy&jZcl?5>SUfE=fEWae4A8pxz2qbs1p3@R`yOkVjKAm zV$jM(F$PabVNx4|?8fJIFD0@?4_<>wzL>2zvfFu<*D~*VumOjd?tQu8P$m&iCbK{X z6xQ`r4=20s*--!jq|cn)x&*;&@BU~)_vv_=_uUgUquZ=*=G%yjUmK4lXOFwDWn<4} zI+{kV*yuambhvL ze9}A8P<0!c$4cLYCxPNKiz}C_hAwYC%wz{7sb*J*7@nnb>CCyVrIrBQPn{!I!hX&p z<9Ln{6onVUziLm-(B?LdS3@!XGioRUqx>kcFr?yy1D`C=&!Q{(jWHec5d zAU+bz6VAPlrt{%`XlGdG-LAT(iE3Zkvz>12woc9-Fw@APlY9UsDJS#}qSB)gOLLz~}elZPXi z6fR%sx%QqRd>ekBM?jW0^K2s^J)^{j5uSe>V5!1VdV^-Mt6 z0oA+JFAUX}RmwnOn-$p4(r<+!j9cWvoR7%(y%pa9++iIX#9FMt_1~kq|NUS8I4^qw zCtZfhbcFu5CtdzeeG4C3DL!`G`Jc`mW@UQl+N1RUQY%HszrKu0|97nvA7AtT$+^Qi z|JAVZ-?084Ti~#<|F7o?`)JOFt#o3zrvv??S@4*bQ{73C7C&jvAofrz7`+D9*(QOC1a1JNh%UBp_vflFrx_=d)e*tg) zQzu@_S(2N{mGu3O8W^fZsr9OfB9i1-0v_In-E0l;1J9c#OErO;i^hUU^K;qrIrlIA zjn{|hdu^uI&@c0gerL;f7bBLlHnC&dB0eZ1Ou<1v#(bOH8?N_tcDS9?#ucM#G8i&y zptTL^9~nX?oOSA@UC*5+7st)jf}Uw8*2eDPpL>#`!#z?(w#RU6!I;4n9A4b8$qa86 z=^u!Rh|*+xe_i*8B!$0|e|Gk)RswaiEp-DbnQ zVnm`s`2tq?y@mv!A?G)UDm(JA|4~)t?tM$WYm^8#S z4wUi4O@~ko5_%1~1dcecLnUXLoH2Po2}atulax5h8oH&(0ha#smK)Uz0t8}%S7#_5Pj-M0(+4jK(H zMQK9LNSvo#!8dq@mdx8-e@T2k^VclaUMv`$v$*e?^a}W?lov+8*TT(b&FVPx>~n$% z4LfieOtE?jT@~>;T+5PkaPNrhA>(`#wEMIgA9gWoOJ3Ay(Pvm^FV#dpZ@hKKZ>N{R zrS~ImsohR*{3O#^?MDLY37@-p!Vy~v?)g3Gj5YkC(B_R3<0>PsjGD+s*q)@0+-kfa zK{vO@Yo4RsVkcDW-`{0^SvIw@d$SNimrX^r`n0YoQcf;C&(yxw14wZBKGvb42aC)i;=CAm{>wo~v zf`Xv9Dmg@HTucGkad~|HJ)_@l`UKUHa*buWGBK(_6tC_?nk-p4+J%Om8GzcjLa_&t zEtb}8h(Nj~8)}=@KNcyAxQc26tGZIWzW+hIQE*TdJf`C(=Z6j#QiQQrWKye6Fg$s$ z@TJa1L<0By+4m9R%$~9oRf)m4)#%C&d=y^1-*r`s#Z^f^dOx&^Ki{DHyppRK-<{%q zD^mJoq1QUseD+YBwP{LUm#~>CMo&UNB6o}QQ$g1nR@4_+ zAL*Nl`P^$RyYBB!^*P?MwJW!;EsK#g>{Eq~ytkr8Ns~nDLEdV})z6nW*lS`dw8g0kEyRbTAYV$gyVx#$vxMIZrZ*o!?KV!7l*5XjC}0Xnl1H>AwP!|X zGHOWIdOU5$e$6(ZZiDPgqNpq#-t6pMQ98&Z7GwU?)vpAN$r^WgwC_o1gtSFsb<1m> zUtaa2t5jKimb#pCDLbwE?>W^~zarRu*n)c>N~vQTi0##r0~(oF5;phsvZ!EC+k65+ zFG5Dp{#k41ontzW?6X1e#OH0(rSGJrWUP3f)Z`a(m61c^@ClUO+=hpYka?lt_s1s_e`XA#M%vfF_8e$yhB>dl$x~G3B}Jb9;<%79 zPwB{iZE2!AYfkb#e^)LtYaOo){m;&Vl5Q^fhr#BRQ!|#%6`7BrBLVJIPu$V zC4o8wgrE)E^$ky~Ymt`7VN;G!CseQr@0@bz^Q(~>u_?)s(t};3KAHD!6OxWl8Z>F4 zA~~3UajEFSrS5nWFY;*#{b%+I-Z6C)6g@ePy3;|ns|b7b*hk$blr} zsyse(^0(sE#|zE3Cmtq4GaQ73G`3|z&T`#2-wiN5oF)X~_bNh}WRAX*i7u}X2Im?1 z@tIp}P9(mfx=|{*g#QuUTJk!Dd{!)iJQ#dF_g9T{SxHRK+PoC z0dM-B_SJrme=4bLnadv6nD0vxVZQjA<{N?0pd72%&&t5u{SO~KFd>33-X4G1`Zz$j zX_S_~g1}V6rxw*;oms-CK$7NmC~G1jeEl?X&Cr zb(9e%ud@e75)&WBfwKZsY?&Z9Sc6f)Q*xmHFMbE(nc8Gi3+{UGTaxSi@cYX|k1WG% zAsF{p6YcS|BhyUk3prQ-6)~z<1qc6))h+YQw48w^*~H1IduJdkMJK)`gT%7W)}P?& z-C}1*NVEy3u{arwrY7iVtjtfp+A68@@x6`tqQcwv7|CSdGi>N(h1KU>LZ(L8EpjB~ z_UGGc2q&9#iPAfNOSfUAd_*m@9d}oI!x}OESF%3IRBpJ}($6E@Y4YZ!D|55`o=n)q zlcY6pFgNg8OcNcII$P9vsQ34aZj<hDEY)9u8t1ha!SnBjcIH?Jtb*N5>I$hbl&1JO!dhCwTt%_9swvsc8P5@X zvnjnxT+g3PD_LTFZNo9+V&YokVNc~1;FH9^t35sH)cm7D!)%Y_I2STMcfxLZr^n|b zHF}xxz)udMxR^oeM}LEz zLSk|{GR&D&o8A&__~e5d~ubCjYx>Gm+w`@U+HKjP%B~= z|2$orGTW{^d#?5~#w%4O+jp$axIdf2w0k$dG2LjS{L{j=pnyp|Z9LHGX@(oo11g=512b z8N|sAb4#D1ivF;JzvQ<;s56OG{d>gBPHB{Pm;=f3hn94_35_zFAB5-QudkDX>voc< zk_^SEhY@@3j%j~fT6D9C9a|@U?t|{$??Cx63|qr?16Fi8<=S~hcKWCPx;1Qs^Lyy~ zD*kck$VH4ie^b2c0~XuNT4%AZPN4KdcDReRR1_FO4J}|P}+d#7p{NflIQuN1(QDB ze|O*GH5fP<7&mAgt5WVw=Yp#Nu2xvea9~li-?#RT>p&v5tN3XR0?BKJd$Vkk?y^fX zSze2UYox!_=aBQWbmt)rpBf5~)a4SG33j0iqWe6bm=M}OH`9bZlYjANtjIDkB&PuR z`p*VtXQVQUr+UxpO2a0crCXshCUV(mK;&L$4SY+ZkyL`8=JZ*#JQ=q*MVWQG(z@`?V9-9f`71?NJc>Y@&}Vq zdy;E(Nj}SaS?ZXpW1(Kdq`v7eN_o_Cjz?^7O15K( z0V`@KSg&$_3teq7F4wuOTjrwBjoEbXkoN9mnbnxG_^( z0jr$>$pBpYl8{%e)=sQTKyjT8>PEneIUbZ-l~pCCxTr@=-aw*@(;Etq`mS#E#Ubu5mtk-$EOL{&)mN*8OC zzG1;xp84?RedQ1pTT-I=@DpzecTm4xK~*TT-==V3__EhsX_miF>44NL8VjPL+oVcJ zEkHju&K=du!I${y@T%P+b60W($KN%y&Q5?{+l3?N)H%^zX1s^*4N)Tw2kCS={x zn0%hLtF=E8rZr_Aw!7<=(BoSa>n`}fOF(r(3v7t8UEhrqU*S2qW@{jsj*DMDfqeSY zKHg)9wvhoMVu&suz=Sub&~$0KMB;m)0WZUtK9h=oKMUBib>8LEZriqIL)5O69wPSg zUCBq&ho7`gdTPpW#jJ7O;0K2#c8Am-UrZaYVvJ-iD1n!{(8NDq0O$5- z|F+-)|^Y*h6<_L{n6`_pBpm=tY$kvFSMB=H-oVsmZ>5c7$9r1H#49V6C&5 z1MSUbgvG~5f5Ed^nzRGbu;%s_cVG(2vl~vNwKDVYfet@`u7^41;18B|pqbIP>4D$F zsn=Z>4CY=P!3RZaX_6J04!}W#o8~K+Jr+~PHqwyPoB5;Ob;HZFhCM1kW=28V51lr; z?M2D(PK$`TlY<@y`thgQzP)=<&dNt0GiNQ73&*v;ub zQL=xg_}^19I`;n*6utPDl5L0}{6Cb;=;1pSl+?wa>T)$LZVz~0xHpcCF_Kt;QbC?1 zr%t!ixx8H5oT=Wgmrf7uR<2V?RdwZP@$CD#2t ziL7fo#=oEOtGt@Ecw=$H!mNGyXXaBEwV@R%pJ;57s>P350^#mcK&Wg|EAac{qdmK; z&BJ<}j%g;N<5+oXC!+#)s=}sCbLrSx*LF&_!$kdqQ8RdXzO^m~C{6X2k4co$5o&5n z7=wsqTsj$8IJtzwgiVGho_@!(BHBbRV0B|b_omDC^`?s#5+Mde!Ynq~H+4_PH^Vt3 zVl+U*Bci9=D?RU}FGk|MK-S}6hM|T49UWXfU3e+I3fK5iY)5TzDyMb4D}Cqc>AQK) ze2q;kpQ!{nfqk|xa}Oa+sA>Nuc}Y$?y<9upn7hKGetEZqiQeZmyBNq^9!X6jP+mhV z5=C5C!!d+-s?)O`xO;P=5s?8^XI33$@2kPZmdLiAl8`}IY84nj})H6Cjn&AJ*Xu)LDvflPwsp*#7`KVm8U*xMP z1T$EMoPI9E7ymPvIM{2#?v6T@7HsBmhg;x_nS)cEq1?nQI3m)MM=rOCghS5N3QPxz zAgottDHH+oLlL7R9t|3_F#M>e{=x%=v*+yfd42c0V^3*bGWrUYb~{w}^Lpe^NtM>e z`$IrCHA6bUv~ER4kq|VIveNO`I>f`BT!-N&I8w0ScGr%;zBFlbm6bA(HL3?8t=Q%$ zi2rFleVhshr4`*>ZFAc_530$}w4MENO2b)G89@dqUtTTpm!4vaO&v)K^#%Padf3e_ zzJUtEsV6U;QPuNqkY}V|pG~#yyBz_;!i~?l_M20JG}B26D|80Pv#66qBb#z`0kML2 ze(UV*H8G)@>EPr7b3Klals#F`OKaqwQW0r$<0EQ=*|Md#?V6Hcmj~TPc!Tm-aRE^G z29Sx*&Ap68f*F(2B~pVtd3YO=p3#&8RfsI)a{qz@!*DKepK&%Fj51D0bp?QYTo@nG z9A7-G`C_@`gOQ@kXi9w|tR7do4lW7lv}Am2wQGiS3pNabj1SFTp*ec5 z;7FjO255F&MH9BeFY3}GrG@nGz7Tq~fYAD6i{7H(rc-6ez$tzxl*g~}Ab4rMPJbzM z(*#waxzy)HZF&hA_YzBE`1BrOGsZ_|f%T3jeGu{C%+5i{^k*5s?y3;)mM^@p*m^;K z2zs;>^j+h)3O1P>QAth`!-}y~?|MCU=y3x9V;5&iLQt;x20x3F0Q7WcZ*h4d`fBxX z>v83oGa3+q_;9o8PlPI40%M}!*QnJ92U{hnXa9z>E+l^^rCRsO>DrNz&>@6BgV5S9 zCbY2tar|*zttqI|z?zWJxw}=t{In~WKmwQ0QHy_`VS=V z@?e%f_{b?`oSd%)7;CK>^}M7jM3S56fb`%_@`H7Yld8P}o8jSMwc^)-OK9I(Q%IMz zv2TOiMRfB8@F$)}49gRJLe#2xWS#E`(s#`d zA_`0n`b~FxOC>IZ>1wM;OJvSETNMvRUFc$%Wr~2KHkjq3umeH2S{1$3t^%o-dbf2H ziVnvRcD&T;R0L0J8@nQA)s+P4(o?jYExdBKWxSvw*usn;%VS9Ly^v9^K0ewd2qqj? zoB+vfqf|?=*Tg&(X;o2$n)>9NUgwv0&hY2b6W6EVtk?62Uf zkX*_oE+XeQ(bwGV_7Y`YhHzL!yuzX`G!#|+2F}e^B|&_a7+XkHOM&M<5niu#+o^9ac_NnH%syMdCKk*GY4v=#94xUd8W5uzwLFP!V zk#O|#l)wJel$J~4K<%uer0WH0dumYDQZ}n;jbC~+fJpJ3sT_evRhAn~m}IE3^y~-H zdT8UP;NZ6oDE{T$q6yyLK9}5JvA%89`w{!r={;4;cGMo{sdd6DAVwtalpKrJ22+$C zo#$KL`w<$S8tZEh^G3>)WmvukB#49eqXj@zyxr((X@KrY0tgcmHJ_675B(aDxOs0wBlN-zF+uLZBsF0931e1Zs%lIkGBLs1T)0 zH4kxm)uEDs7`M+?$qrhkH+gGsNXH^Qw2DTDFVLZE7U`(lfg{=7C3r%wLollXcg%(R^LJ)lP{JlTF+Q&}>D7V?n<@^SqD#I;dQhwMi1n(6 zG-Q7NWL0iZbgZjE7A0qvzb_KC=JPlY$NQ-tIiHy7i<@ zVckk1DNtOSk0H{5f8hR5#=MqnuXpZIfsZK1LFW6tnz>Dg@XyJ}?z_iWzccs!+$ppu z&PdTtlo4Xz22(774V(ls@*nA<7fRgBD9Aju(zGyShf1k(gAfgch31oPk#`k~#XvdV zUJg>jnLj91C|bO1Gn4)dQxT3?YpH@Cc>?13H4O#OX^=LfZ?{I9x$sBMa-CL>>$A1d+dD~4X2>M3i#H1gw8VcD@q9?!;JxwR^vB@QAQ-zd_whu)#9bD=;tjD~>} zz34_^eFs)VA99cqgq00$to>%MdXO1H1hkH%5dffSl{)jN`;r#MK}LY?6_9OjIWk z*(3a(XLS_$yWituX&@4wJ`+B4l>}jqcrQ_#GGE(&?lG97Qg)cBBr|xkE1&`=)*3iP z0wiu4If5+PBg9V1JFb|Ae7-GNkEAy-t!s(&PjU_GglUlj4)Y>~+2e`0Q#rfy#a1NI$I{n+ z(bL-G-uSeSGgH`67}O~qFI?muNopdy@9{J}{g2PYYhEfi!7DVZ`ZUa7&V`WZVhZTe#n2!io|Y#T3Qk;7}>XkZ~2U{q`5qf!_sdFZX;3 zW`)Dy66rLYuB-_Iatp7Nn1ao2j>qzu4? zfLu|*<4oJ8B9V!>FSfeHd}hyx2>nhpxK9)B^B}|(S5t_}v{DeO`NV7%Pv}RV*l(73 z6z+=mbd|smMZikJsKt2}f`2hfP&XRAfnOn^E2!^p5wUG_tzcu1X?g zjn3p65ml759$*-q#@)htJN^4dLu(xLNTDX{Z)36gQaH6TP&U~saWuAuwzR!Zg?McH z7&P&OLC$bp9s}094k-^m{8b)lXHjx|AxaY05v|Q{?`pK06P4MOU(-cGg;OK+prk5J zC4H4l^0hC_xJaJF+H0<1_L>Os7+YVDU9?q>jup0%pmiALXT7R6_Cm_y?cuUSP{<9K+oUF+YvE!JT{F9Vz`yu@O-Rb_bOYqVjdSZehf-wWfo@z!Og!N8TtzsX50 zT&WoJ#~EJW;1M=XG1J)5W>SuplVhlCu*ECR{AYz`GBJ=#wP&znvgsV4uJR8M{UFYY&$};v(G%EOv3=9_0#LiJu>O}I<^LOP z{tsCBpQFtg>HaT9n={h=_tED6uK7O(DgP}z`QM5zXQpTQ+vmX1$-!9P8XCfE`yYwX zhFHA!i|Qd^TP;(kqL-8H4UC6hnoXmnA8_-FA8|cV^FQ#Uy6pQs%#k3zQ0bWos#S=g zCeEJSp5W(xWu}fZ64%G={Whhfq<`r8>`1Vw3IcVE_j}akh~=-s$Yx=ZJB!z9q10i6 zY3#OPWx|K$HR8=_cqmI+b*K(xb#a-x2~4HZhi zeJVh+b?m?zONwF51yzqR^-xDb`7oS<9$q+FAk3kMevL82mt#D3QRfc}I8ViZ0cbp7A=I{nnX-NiERpL>jP3%h0rw4dK?^ozueJxT9g*-3cX{Ox0z5?)!iu` zYmz!d+SgtRK?8RMi=sh&on>m_qBP6u#?Ccm5*gcQy^1EP<#H9NxQPY4Kn4vyv?=W| zWjP;VweXvxyuxQNY1`ualO)-;pbIm*_wyBtIKJoHvqO2)LflSkp3jYtRU?A8Hm=4C z#{Qoexr0@bCHxpJMel;Ctv#8zX{U$ZdD&YGO zfuAcHjW3AGt=82+F@;9qL7MW;#dmaDt`)@ywM?|dIVU>dkLx5l4w6036wmWZ>_EYZ z7M&siu6lRQoMRihgUxS+fuNbo28u2kSmt2`(SS`asx$*h5rGels(jj7xj_bH3@#1T zK}WJat@6+2fgpnQZLREMm-p#~G*DecH@JyXH}XZ1&pqyc`tX#rOtfrJeugUj`cMy2eJToV%ze_U=aPR+Ry#wQO9 z`Qt9XhPbRWZ>lO%BP!{dlNR7det|loez&;@HY}0tp|L#ddQJ?s%yloZIA2HswZArL zIo>em6Flh@?=b z)RUphKq>qzDyq>NnIYEw2)T&-ECz#jZm-1pp+?oqghN34=)4cT$ZcIG)Uy;1c7OtgdTJiSP7p6O4VbA zA#DAGO}%Y~S~3T{D+ot41G!>y_DPoE(7KVfMaS03r0G5 z3jR|-2I!N>c%SO}SoytS6miC!iIw{m#Kv&B3oiz_Jq0-zX&?@MFQ(wnAQ_8b7enrX zc_!l9-H7sISqZKqusOqO@04A%(Wtg}>c(nWgP)o6;SwxYt#~s35C{**9jrUOA0aej zzPNye{FS*Vw{NW!T95@zoK?aQRm2RSw(;jfe^-RUO*br46`%wqFVH}uSzUsE%q_!{ z)W#C`8BH$QLJ5{lAOTW?6|lr(IMc2Rg2R$}Z`_MayDHrWg{f+vu3LXQ@D7-3NSk;oI$G1yQ&i4Bi*SMK&)r-htSY{3B~!$3|CDBxt}THXK9 z93)GXkNX`fJsye~t+kVW^CcXowvRgf`;^y#1^l;g8f{48hSk~h3Bu5H4L1T>4^Q8V@+y8n+HZ0gsy&6XMk&9TQOQ%4nFD8_p;x25N!K!X~kPxN?gd z#a z0{M#EM$%|+LXRcbg5pMJGWG&uGBA%aex%`($sey`EnuPLscj7D(G9NmhGjcr05#GQ z@MvK$%{xJzlcojGPb4bRdj@@r=u-!Wa-lgR{Q=0r}&lopfCbFYC zxfjsI;db$Ji&5a^W=NsFT*Y9$Tm=G!%9jtlVT>r!tetu9uiUrd=#dnh5l6=0eZ^ciWM@>7U|0YXf`GnW8M)KpVJt7CO+FaQ=HE7BNYL3?Phm+ZXH?Y*lhGN@Z|JUtuO>lR(QLe5_4l9)T~Z!5;~ zuSokScTD__ftaFI!R2RroXP`0i8u~NV)LumaFlg&Mse;y;71fQbPhN(Ui*ERE}pRCPly=)m&UF@IDGG3&pQC zLpzSE_;2js@hf_ zv+455*a}R5c&1ujY%Lk^??B&>?(8NO64uQu@7Xmx6-4~+!e7n?zs=2LIE;@97TiSp zV?>8Q2d3CAMEroqpg<0EzB2wWc?N7nlw6AWcFgpgZcejZR21jtT|MP@7C?JO(|fo4(nZ-NkX_I`P9Ouj zFOAdexU#vhKoB==xZA+TN+sn&7sjZfN<=AqRfv7EXN|c7bRjB?^AB2?5cH|}>tT=X zvr4RqrY}3rS1_1$_GVa}JV~n^NREuO=uI{jyFzyM^>HuV)G1mF@7HqQbWGjl5<1P( z>O^*1ewB2xsVi$SSGjHGK>a^T#&!X)-xwBW;jh1$=$r=GRNEX%RHot1u$ii4!D2)yvHd6(5dbw~ zylT{;$?|sa@Sbf1sk8EO_e3)*SDuD`S~Ue~%uBhwkq$2qA5laC^A~~*_RFU&Tv8N2 zG)u|-i4e4+1C=xE@Q%%_gj}zkx~ffrRb{GW{kQGm=xBClh0sH$xkh%kKPz0XBZ$K=p!u7 zF)z447bacJO<)LP!a*SdHtI_oQ3okV!xlr<%7=9#&mv68r1ITVWV22nPJefjhBupI zl*H`W9y35Otaw6ud|>`^4JruML^Q-xu2DLMwUvppMDA1z*f4)Ty=-y&+m$e|`wv3Z z5IOAEFIIk)ScnxKFEr4HY!-LPd6_46MD)qhPUu$)4*S+18l6VPTO{iKc8M;TMcP7xa5$JlT&ui-jX1wLjnh9M=`gpR$ztKt^ z2~_u|RW^{gE>cq+Duz|WwGSv+zQeNSKn74~5Oos3O% z6>G}JXtehc9^=(+g{XQp2*WQt{m1=6&GZuW>gbmZ41+b$H^KBg!N@z$Er$w=qK?f3 z!qQ_4om&!~+s{u}GuC+mbik7g2JitoGJ=XNwt`x&{a>I`U*@YD_%!jq=oSn05vsqP zb$HmY?^D_VvAWqWTWSv@RqhI8UpXtPDg1_IKgQpusZ%&>k#DqejCFNL&cCGkx)9!U-5(4K=D833`C9%LexxMICd1`!>v_BD0;&kOjZ3b8cT z=-l%pw6COGQ;-^`2*vL#6D}rKJsstzX)XK1x&}eQQjY`5@Mu^04F1Mi8jiZ@L~uDa!{W29knvL?kRVi{%SP zk69U%p%(CpfZ4GN3s!N7PmM@`z=}zq!3Hbjo=dJw9-8#;GBn#MP@ajibVweEE@kpN z#&6$2#MhB)uLLAzv?Ip*Oq*|Z2R^9$UN1EonGT0VKf{(lm(uP}Y-)jly(u}M^B}^# zs(;j-1>4E}B|;}LK2g$1m%AzIEz8`y`HNn+2^X&rrm&l(pk``tMdrQKDV$~RM#NY5 zI>hrJivrFEC&LjC)|k$Bfwu1OoXgDRFb#jDyHgE2iy7VkHkf5LZhSw)Wd}ORQZXK= zLqA=G(TdHxzpq3}$-ApER+xG@!;Ld7Y_gAH-*N234Edb9V12Iaru0Q+^BReL3fWn> zPUSLLaV0zhxh?KdDt}~u>O91Qt>L5%iMN^Tta5v~99PNQet&2_uKyYH197$uL@xta z75l8}ZEiNb2UEoy9jVA4Xt2&+X9>`bNohDEt*)dV2Ft<}CGk^9m0}O|t6p1g zN4DG5n%Km88*Px=<$D|7qVc*^zPUJW!vX8&hFGj3ZR_TUzyb58#0{Mw=;6|KadQII5z}@r>ee*j){z1in ztzo}^aH*s!?c~Eca-u~7>ymFth2^GHIH=7b_gzCR%)n(e6qs&j&BY|7aROKSIhvlf zXvSprtCUPJ51R!P_wuYUa(wc`^qd7*2D$I%%BR1G7e(sCZA6*N?Q%ro(Wh18sVxZ5 z9GSTKm@27%;fm*ATzux1RHVgjkH-U^8B@Dii?WtsnS1qwn5X<{nOY3!g~C`BNA%ca4n%KUh&RbPLXL$ zk#uSV1bpXz{RHQ~mmiP;l+HN_8<#(8Pd!a>l$VBYo1L)l_{P|nHgn!}W*i@O zZ$mr)+Iy{}@oIHB-hw@kxHR8&#>7R0^In;ohj98{7AUq4X<~e^ zN(SYy3O_54fhDakYI4QvprA=+qRFwe;PG{LR8drvVsNZfe}Aw8buV zKf96G1yY;!RRrz}p9mV9LFk%(U4BE8P z#zyA)|G%wr`VPi6PI&Z8jQP}80r3F%m2d5`R|(l0IhT`b`fpdNk`lw;V&;FH=dZ4f1&`_94%7b<&Hf{Gvom&ZGBop6@fRwmSAYe9^kw+FolnV17Pq zJUKtV2abkZ+UkuPU9?er&Q|Q{X@0Jrc=gFuk{MuZXZqJQ6N1rJ*o$)wquXFC{Gr}^ zf{!R@s%>dbVdpkzpyx1ox;r+hRQ0VHc_2Cpj^Xbmel=+0@d_&!hTo*V4B~9T=IwX0fd+ za83_$+R)LRMQ~H8;HXMc-u}SN_n)e_O(H)vg^?j@D8aSTi zLIso-XE7oC@F=^Tnz~wg`#PF>vh(5H?Ae$n*w)d}otSQQ7SC(ULO0w%Ck3YMGc#+1;`7*}iOkmDZ{(W2O#P<#WG#h)2OjS;=sH z4Fs8RU{YQm=sCZky@kXGmx*X@+$)9ciW59IojtWVS7_h*%$rw+!2I%jOW=WGt&dre zviEe$YczI!WsgIzKG$kI!qSulI;TBHqD^V!_gXJLw+{k@-c|Z1eI%8cObPk=9W@T%XG*V^FZ&Wr|mUYmwJ5xqq6*8fbN-U5BUNWJOW$le)e z8648|@-<+&R}L(IJHpm|d)V5V>g5V@P5Ie5K*=3NWQ@|BL{rmIYW|~Q0DW&xlVW1; zy+z_DNC##JWCp83 zkY3wYvqLXSh+%6}JKBjdY;NBjkVn3!K^3^RXQiu^-E$N*B5(iLL8&iU^$^nGX(wq% z8ev@&BcGy9P5To5C*soWh}i)GVdy7Obw z%0qb&d&%}HRzr}Lvo13g)ZT_)KS}By!}{p21d}f*r6=ZoB{oEtHVPtol33Qw{;}_> z%4gN*{aYV8s-?tTU!Iu1h;7Y?Zw;^qcTAo$fg5{=ONhKZ$?ht4>a)lBD)3 zRG~)pmQ;7<E$Bc}5+hajwd?$|XbA?{)MQn8S_+ z)hIaG6qc}K%zmLD-y8cI*GH)wcw9=T#%aEo)nw$Em~84~aoxIG%*@UvS$ORFKF4W1 zA?jCUg5?Gr@4?CCMG*`nCNYiQ-Hi{Ydk``~kjb8@{kCGrdGL4Z^Ct&W3lUFf5$I=@ zpt4lK(LODljodiAn(FOCP6vAYv4>W%YUW}0VV07=HLJMiv@#VT+}1PqkbOPO`9yij zH|z2wT3JSW*IgHxyWXZwj4T~pj?cEM1kmbY9|5Kh48baSY;|CJkVSA|SSwo&E@WR7h2vm+#Q3 z1|gxaWQc)xg(w3Zr7NM9u5P@PGyDG%G0tkM>mC2K#PRtR@~{!H$4rK_3RUO}#~COx zY@uKr7BXFg9R^O)o|VnxFT16RM{jChts0CpvM3`Ou-X*Zz|u5Z%rR_%exHR zwo$H~wN1)A_pd|Dkv8%mE60Z$^PRa4)-e(L*TEw?H6j_PHYlpc#6j$;ZV+FJqHWb> zp>v??95o*du>Sq@LN4UUD&cjez%R3cNypj3+y5ehB(RrcC>u_#_{xkigdt zOs#7{qtO#quE|hgkr5f00X2EoE$IBdia5!@2-W9lb2DKvS^uRLRS)`w{zAYaneT{f z0udMF4?dT!tn`tOz!9G<5WiGUv*bf5mxw@vg<&6P+2=Q3f-l&r2-2yUaiyT!sX(*R`)6lagkB>cfv`WnlcigCVaIQL=`0GV z$DYSH;X4pEf+}cY$tnV`n|09y0H&JR zxeyrMBvIAROQN9O8aZcz`y~g2;pxz9dBKrb21$jL81Ji0z6L;jM)WjiF7az=B6E?a z^s~sKJqD+0y&U&pHkUjJ$gE3$U#>d3H2pUp_E+bn?+i`4e2bBSdhb&w(NP8qdE8m~ z_s!<&xvHsIVy*E!2->T$tUE;~^LXkUki-yHKpwHQFVyu3wK0v%u0AD0jnGypc~RzP zo>_;Mr2Bm42JJME^tbaHEdiH@Hih5k%Ees^uHW%K_$iemb?BFL!ZGBB7z$muB&cGX zvd(_TD)WB;%II@c^zdUqc5>du=CG z1C*9cUFXZ}o{k$AfU}J$c`%{!z`wY6SYATHCLq0Sg8@v2PfrXI^_XWbgt@n@*& zk#U_e<0APy0ck?IJAZ!gpyW9r3C4Je(HqmYHlqDr@W2Tm_!vXZvh;@)JD3Z9OW9%8 z2|zAHjrD$35{@!5n(OqRDmdrKI?B}5DLf^p%9Mj>ESl~WLJR})Je?WB4``bLv95l3 zR;C9u5}j&T%9a@4>wu{Y5&bGrAla;-4!cosTSJBlsorHu=NsT*&*SSQQXQjQUo-~W z%p!I>rH~@>#6$*W_?;OAAvnx=O>CKCJvnBB#-s5^aW(GQ+TS}5F+fJ&;9~k^r^~K3 z0v1CX=T5(nj(;7&atg{b^FYd^J_!#1KQG@5uzdQ-Hb6+G)l@KdqDNU;F}Mn@I62lY zA|Ix2W+|jEeU{87dMs#;3+;2_y#G(L_RSDJ^1xtYaO|B^&smF6JV~IVh)Xxu^#C7h z`@tz#!wwdm*iy*d6?8v@n3vmlh`zy|Z72XNf_A%XmhxM$t8l(=rp&&2&lpx+hEBFb zPv0jM7isD)mqHl(EO-GqUU>N1++%*#!T@r*4tL3p(CU%XBDH$U;QYcbPTl6GiX#eY z8yg$iW#xu37b;jLOx*$=ozCAoSv@_Se4Ail#JsdCVNn8KbX~?+X3&1c+0^2!@04Y~ zP;mNY%tq2<>7@4U@6mGTjJA;6)x5mjUB3@(JnxQtVH3XlJaCT9Q>7?~FYQD@b6E$4 zaOejX8fxOhktAb6xuMKSyP1icf!e`bEY|H2D;%55ku$KxGOs0qV*T6oujJ+Z4=u{aslO_acvYZl@EBOZ{U5{H)2$V~^Uf z+S4eiBi5cW5Y~jYo-|pR?S0l31A_y}^Y8^>WTCBd-buD6!oshgzePE+S_=u8`WgAd zvD4UXe1cD}n=ivCSYb~KaKgv`v=Ojuu}hEf?4e)3vTscCONXSbJca}-u~(!vVl-d4 zJ`|h1j?z=xh^5Jr!!Ba5m@*YzgLW{+E7`@ip!AD)KuqBnu1=}%7{u<*$@fM}6Gmbs zq)8hr${~-5HW!*k>=je=S<=SMW|gu?D>YnWD4?5IRQ`@zItEv_78i@Z=Oc*WwIi+U z_#&4LLIY}rF+=#|Bt$b8i4Hv5T|A61`xT9I}Oth2L>A$5}ZD5E^;g$oJQ~YhU*})bO^6c>n(Aaeb@lsZ{dh|Hp>w*3>* zT6=#IHQ>2g4u`dTnqXAbFt>he9cSfqLPAZ3O zIfV6GSyYnrB$H^W6wYRHZ=Ng`)F`FfAQ-n5Vq6_>YCItVlgqghOJAWM9t%Uxs!>9~_qyT9Qu>d0^DJ&s4buWJwgx-fJJvF;UuC)qC9z!0X%V6gL*vT<}8kogT~1? zDG?3p6Z2?QO;`*%W1`l4r9Ll$#Q$AHq>beHMh(VS>n@U885*IamvSaKa3s@YD43jJ zkNl9^!7+s5F$Wsf#1I>pVG+4kXVOO3%b_AGlIumFFNBNetAE#zHgWyNq;ah}I{pB@ z90^G)QDCe%yJr3vz|%BPtmkrFH^;k$1OzH@2&&#`XLz0FUzhH`g!6zHs8Y7l!gy+h zX0b9N)i*71nBDwTSsPak&EV7^BU?j`v>YK4D0EOzoV#vZhCj*qZUIp)pORe%l$E3I zFV9JCMua@^XZ;4v+fOEvFf0m5r(OSeLBUPlvYV*miXXw2{$XFu=>;^w?Lg4`V2((~ zpu)>HZV+;NNW4=g-fiIosl!ar03=FKCH-xQ92*_{uNw86ttfzdICI3)%N<4sAtiqS zxXn(vPIJXb`;e7me_9{m4jU_hV2KWkIv-HMp7D&pr8+{);O`w&CVDOp%~FappJ$Lv zQ0NH;5yt`7U{{&LW=sY#n)i3ob-|w2QSgPA)IUjt$t_j3mbG;bXfkZsDp}AF`z1Vl z1QGH}{F`>_yh(@6B+?~2BY56!Ix&ijS}97e5xREqfZAva-!6Cy2FqRW)kUMcD-hLp4L6Sc` zVp!NHJrd<1aSqcuXJv!IXM|9)bL|?B8b&=Z`1OaYX2o3RCbhUz2l4sdEk6Cp~4dY2sT3Vy|lLM|fv)LOZvMp_{c{!%h)x*~B5F0S*pxTMFiol#D zv)Lpo)^5xjaoQ?f}JK^7<&}7Q8RsKEN zWxF)3Rnhoa$33N05i6Z#xirmHA=Ug)8U38{T*(n2#Qjrfx+E2?>=rPUZOH88vs7xc zwCbsBc%uXjt)!74yX4g_xfG=!>8TM@P94pdN*Y5^-_Fw`x`dL*7Ib^@SjyA&E_+wX zu^vSCZiuKhnXV{>{nJ*yT4Pw6Mg}GCQD`tK85ICV_Dfm-(h5aNROBjyj?vcNH}B7L z)*qMzFPj79RKcn){%DQrN8r)QqVw6Z|3TL|1$Pp)TR*mKTmRU$ZQHgdwylY6+jcTB zCbl^-PTs0hU%eOSyXfkweX+Z$yLZ>>{XFZpezBvissJzbWY!zRPwx$f72xLRZ6Syy zAFj4_PW`-hCuPr5&YhmDfa$maQ}QFmXXF_ts%F;2#ZdHgbRCM&$S8lnoUOzB1cMu= z{Bd~?IJRo_OnwGqnid5lv5;`C)_wTGwy8rY0gRxWXy;iN$YgQMUU(u)dcGvIo!7Rd zRS^-!WJMm`{9115B<|hC+w5WD-AEJcV{`rJSR>VX@I2IV4{Us;&tzA${;g=?%aEBe zbS~WwKjT}r6#nngV`6og-uV@ssT>({EVi+A=!gF*QbSJRS@nXUl-ofx?dPrly%1lO zWG&B7Gz!hJzDgSm?)nB%k@Ze;*&2}sGF@;r{cz`T7jn)u1R3MZ)Nq*N)@UcLWq)G= zZOtcMLm)DoCZQ>Zp$_!1e#evYQUpyJamxV{HoIdT*}}$IN`ue+fYhBWG(+#!_OI@a zPZn4#Yx7@BIx$i%rZ1ue!N(T8y?R+rPV!NsY}9xjQ_T#pWE=B&X(cB40p$=$lNlql zG9Dt5qYP#b|H#Mn?9$1K5VZ@HWl;bUOZoR6e`^FFuQ?)(H*j5t{LSKo;_?a; zrwWGNW^(V%D>u}es3yKu4Nk=yTBBf)v^3HBXSbQmcxg9(wqVQKIOSA@cV;qh>Bo0h z-U3r9p>o@R@&cE@!!`S1Ph1z9I;Rjn>%~R{4OYuxp&|=(ac>XbBCq4V01~Oe0~8Fa zW{p28C>^Y$EGMf3W4h7Eq&0^0_fjZu*=dF1D@H;tBt|>L-yHeP0*2SX)g>mSQe*@H zoTgA{#>TP6Y>a+<6Qpm}$lB7PRk&BD90=;)D64Vb_}0R}#+GoXeWo1hrAI5Ay(HNf z>>Rp3n4x5g6)BiQ=S)%>ep~*V_qob=Wh4Gfl$m0Il8$m3fv`}k&v)?0mVsJUo!Ap6 zMUF)n^m&o$Zx~&t?uCF(VNkKzbuW>iK8|YC6Yc@WFygTgnqjYeAy|hr);)b4W4nV# zTKfQtPUIgt*X6P8%3<|asWKDZ*qONS&~bG(JWhg=LJsL;Rbp7{28>oLnGCyF>?TzO z&M>x4NCf^Th;{QE`(sP;;jCuqo3F8up_IuQw%p$?K78IX^s#R3%fWcV$Uv8pY=J^3_ZQXyVaT1sUOQ&}dHr1YzgB5#Tr!IxO#L zmNBVa!xwoz_`voiaeb?CXrrK@wY{jI$+wVe&Wl7F9z4io@bPE7k?iSQ$ij(u#Tvz! zf~yzje<$~F+?QGtrFjJdkVT(%55E=5>qL^_i~0M(1=5v ztafn(_5~_@;ZpJj>B&;Js`5jc^I}e>@efDW6uc%q33wMderv^aQie+NtB~G|Drncs z)3NdUkw|=VQ=l7mGOtfl+@s`_j5aTHTouEkjxM2BY{lbcv(SnW7CXW@Idf&V+657T zNtsK$Yfi%=r$yNvQ~V>Z>0gT3%jOs>?a`0~+A%0C)`W~lvnepw6%aEUcU0HuDYh+! z6K+&sX0utwKOT)ev+zwd{L~z=qy~Zg0=}7q+Ws<>7-`!v+2&FL%Jwkf=s&ERVf0Cm zN6cOCw+yb42w*00`33do8%ds7y~KN5t(z9*f0Gcc`D)JxY7%CP=E?scB=&hq4hqnj z5Wy2nP{op>MFcIL%LVdf{H;B54j5^S9}(c@R};^ zrGv>$;_I>>MaX@e&9F96&vN9gSzCbd6HAKtXl+w$g5j!vE7bm443nhCzmgm`caV5V zxlfW?m=1_i6gKnSLblF#FidGZ*8%=VZO>%7!)ecW5YVj)C`h28}xzHo_K+%)kd_8rsm*>FG zF4wDW7)9$T4YjH*i}XrL8CC>@s_Sv56teW>{t`Ako6KGkYpO*mesUTY+XF;ngUYpt z`#QNRN9D+YD!TCtMW}!tL+#o%zvLu}3S$O6y=-RvV@AIZGUNnw^)=^7brXxVCzRss zb2|)dD?S0oM@2Ll0cSn|B74MSu;+9)Zgf0y6!b>aCii)bk`q_{!Xdr} zmLZ2F25!AUBN(g=i`xjR(l2By-7Dg=>7>7f7#Cq;g^rW?Zcr7M&T_GaqG8=;Ptg^9 zXw2M}oRye;V2;9;WEIa+;d00~UA}Z+7Zv9~6lZ$BFi#mrcV+&R^Q5EhkKmmm+Fe{_ zq4Huc#WX_)r-NZ19o#e+lVLtM6tNgC#igTE>8fIr^-frlCEEsLtR7Q1ehP+#&Z%IQ z7t>00+<6jQa3$#}=b|i{ARpIm;$^6Vcx&ukE{j<_E3RV?Ua=DyZQG}&p-VHAs+)mY zCQS8;ihwb;CCyhEr?zx@^v&eoKgzDdTc)?BQYg!zk5~*61GEZ{^vw&%Fuo$(uVG$h z8$Xup&HP2HcQIMm;M0NN$yt+Bzj!FK0N0qF)|*E0FAvX{%heLd5UI64dU<e;kQmTQjC3Jgxf=Cv)p&hFaXb=CmyV*Nqi+^?*qXs#^=Y3^SC#n1{ z4$=lbCH%M8)jwg)cqfxs{44G|oQY2@FkBzpYdOM#`=L6UpTK!>^RRfqkew3|ITtIZ z3tRLSF)C%F_J=7KQP9(M>>X$0*~XKb*=rJz3ZUF*UwSKAfG1 zAN*nB!GI_Q8L29-j+BjXT!tbLpM3z2-3HP?w*P7|G_I5e#BB6N2*fN(wQCmywvP)t z+Zo5kOg5fst#}5GY%zzOqg}$Q=y>xN$JGIBYR{tMU`9o;#?vBROK-r~X&BII3VfLD+`8nz;b2`dqkV+LbsAMbmG#oa(qh4Vlm-`8-1om*g@D zi@h_ymsqZEmrMu%EJOdKthqXmV;Z^9Rr{+|udInE;SH9YS1R!k7F614#@~EuJ4ig( zvWY!bm(l!#l-ZD!J}a8`yeU~#S_mo&ONtORW|CXJ8yr}5wgCcR5T^YCt2CV|`?02o zgm_Ax-jKkxjK#McC$ti0z*=#cs-=Qv_lJf$>bsF>Wkj*y8UdM@*`%?tCtPzC(0H_7 zva;K~5UQhH0!wJbEl^uZylbU?7IZF~(l`yH_jI9qp3x_p8O_!X0%a^-qnD-jxz>qE zhR%B;q{<3#g|47=O|*rU+V~S*yFxzEdB*BC!eCUlMt*8Jrrx!d7}8mmEcRwYQt_tS zGPRMvT~g)#V-qH}XqSO9O*#RLy9i=yI0dOZqmOjV8W@qoOVk$LIYk)P7uWu{U z*ojhpw$Uqvb&%c@b<*iaX4CtMC?TIU|%u-O-CBWA3*+0(G7>0;-1JnL|T(xq^32zTSjVce@rx$DEP4( zY#OqmI;Wz(yRzCOA>A{j$U}N1M7hy-^%h7va2C>q*Ig*Wm|ddDe(Q6Dz0bCux!$*% z_U_X94rwlY;5xUqn6vX26kDvxN4iw4MXpevC8Xe7nWXE+%-b~{`?_bae1N0E2p!Vg zbwy9Zdo2w+ZZP|OubVCNM0MBB9kN1=+nDeyIK9m+FM$*-58z7B z+m1H;>OVP$^IR(ycfHccrbrKbd<*r3U|u_96~v=*l?QeFJ7Gm+>5Kz3x3Z8WIa?H+ zfO@fmuocI+?b21Cg+uGn2);HZ4kCTa+l@FiYud?!iH5l|)U_x|KDb zAd(9;hhuuXu>{a_G7lBDbRIFs*_ef{*4GI|jmEcg!GQV=!P;|mn2D#~13^Y`%9`Ed z$|9fr?}rcIxIWmZ#XReKsh>MZbGHUtPCi~Apy02H&a<&3f$-yTUt?K#$u;0&<`)U2*-v#M zIg_+qJPjdi#+0$R{zM{TCVuzWAFM_~vh@|YnP{MblsKxZKm1&BH!5*9aaZI<(vd|0 zB>59?OSU`fO?9#soAm5H)Ojp5&Y~b}KGoOU1EoBSV@6wzMrvAD8&XYxZbEbE3;pM5 zHpCc_3pMVZ;)Q9^BNUV?zIYeOXKRt#fL_U^X^r7(|E*Bpe`3aCT;f97@R#Ptow*jL z0ft&F&tV|myeJ>DA2UdiYs!9uy{-mQaB*z7%0uP;la6N(Dvy0kUQQ{#=)E>yCf>kP zj_-ot8m#-6R<+J&R}PSeZZ(hV_7)M?NE>dc)T$JYlKch^1stjVZ4}?P{Vm>iM#8L4 z!}Z+HZtrH>0?GJ^Qn)hJrylF4&-&Gd*T#FYRbXy0cKXYUQ%XuK=4%L(mJMeQQTXNLAc_uVFM)Su8 zp9>XRK3wMyGqlwST58e1GCETs!b$<4;dxdR^a4}E;1#nYPLMYH$>w(FHQK0z&~v-m z?;w~d>51kBb2nQTyvr~`;F7~5K^U;WL;DGZFeAm-HVfXyDK(~ff)z;36`<5Bx3al^ zCUfLcjN@U-ZmY+<2%>kQw|L>UiV>POj^}MKqI;zSZ7L!3% z?6MeVq`KA1l_(Ew%Qp)pJ+-s8&%xKRy2;eGt=Ty>fam z5G$=k1S4ZpwSRCn=d>vEF~hLqjH$LCY;bWXA!Q6F*dpcZRBQ3J5y-i4w3$4Ou3{D5a=-y0`gsUeftB^eu4f z2Y>FOTUZOW4tY$#OlGYxQQb<$5`aLlt#qvXY;ydcMR3FgWk?c9Y0OO4_9TJLnAMPi zc0*9mGrGKp)SX!&_LO5GT+?Dc<_vqJ0wk?Ra7qvQ6Ue~_gkPxx=!I2tlvTg+nsqH2 zO_){YLN~BHvEVEgd=gmYAsUPyPw7_=H+!*1a6W^8#1O0R2xqu7Yzs^)Jh|kxtD>sj zbnNtE?MZodqcydQHhIPYi$5~feo4r{9}h5*m3?>B=MBoHyo3bL2|Bk&m?`$D zkGs{HTr_>}@l$5He*sdc;3uZh&%Z9;Al59TBNbO>bN(IJ9N7(SuYL7g zx4Qq-UT<`PmyneFjxE$uEgaF-yi5!Ju9CeUvPLpO>rGc?F_KY8!so=L_G(< zrqjY4>(@S2N?NH?kxGvxV`|{K1Bt%qJVz-;ACptWxkorDA)8N63p3GJY~}y1SN8>e zoze-&krn^&DeBWujHIqMk16)#H&BQz7L~A8BugFj6wN@eApg2E&%_{1%<}A_i(XE; zF4yzjr5kyc;aM)?FYGWWgJH@CGO27oVfC2(bB<=q)a?z=dsA`UT5;`e;MO+OeE>T6 z5crFD3!i5{VG<(>mHMIhI?l9Je(}lNzyr}`YfJTL>(c7RJmY5_apT^5{@W@zogl&{ zPd5HN>e@eF4fBx{*QuuqIIGPX`Fv`%x+5@}Pq)5fEBvg+xKWJYG3Sm}ZrX|_9?Rq; z)4VJ$sD|h9A3piLOLfm5HKjwFO3wR-CRMJsSJxW1saQM;6EC7AgmF?w&eqgG2%85f zdeK1pl#3rji3&_yDu}GgUvLryluQ=JP_8V2K{NrMqZkjUUZ>Px_{_A2cs+zSMlnKc z<5N!DaXMXUsm?VX(I-Ap8}*5~&#EPHHdpE#&V1M){>6yExaO5Sj%JPyd%}|(4B!4Y zY%cyIp&xretl14gJY>>?jC9gP>Z*NkJf73*1+NnpXar-=@rN;cPxy7 z<`VK?kWxPrWv(h3A*|k0{v2K#<09@$zcr#4LCItM)Qpq6`+av=E8EazgJ=J?7tbjl zF7h-{a+K+<{-E+Mol&_NlT0fkoX*(J=fG65SCgebfyQ*Q=;Qj8+f@%VPj*=K$X0qLvBZniun7A|8@Z6Ihs`ls!oj%!HrP`Nk zB)0**hL@9zi;t6+pZ_nH_ahYNPCVH$LS*iONUsK{c-G(aV>1QB;x);j?m4P`RgGcp z&2xIEME(>Bq*XwY8Fq##F#>^paOx;-ax**MWMj#$KD(Y-$I~S)-n*{Q_@b98M1eU8 zoH-((cC#RE7C(hGX8!R6ZYJqcno&ivhHB%kw$8DQrp>!WuS#*sTpDA1SIh_4E3>IP zn%06h7Ph1)OgU9r7r~Y$#=LKdUi3q8d(eURUgNlq7$!6^X~w>p=Fi7^Zjf)dU4FqF=6A;FaJy zMtlEi`|T%yPi2E5Xs%Pu;-&Gcdo4iYaw}crw$cCb2nrEtScB>a!jhY{7*sV0`*SiZ z(!j#37uDWCb*72lw9!k&tnWw`@722emP)3=Z+Nv=5#6WSY`UC^41$Gae+TOZs;>lb zNrvS8^9K{Wr-yO;RXZb^6y~&?2~7A=m;u3~EHTE!Ac4lHchCsRrISB?MK$2q&WZns z3TT?7mXTG64Hf*0x9Ghpwl*lpZ@gBzwd6a@Q{(q<;oW|}gi@3^! zUm_>})buy`bfOpdU!S|Dui4aIQxj6%Aa=!aMSvCNKt*rxT5*Qc)g6Iq^|&{VOspX^ z=iR_gQkZ54xkrqJJ3PkDOl7~DD1%))dBx?2_c;>yygLG3V(m>N z{eYZu37145ofH*o`o;I&Oap6%>edga^M86W(s?n-gx--BCrHll2N z4sP=1a5hOl94Ae$9o`_UURY>W!T7!cet+^9VIS6xz2*taPkg#pSC`zsYzv{a0-Wkn z{-xx@1@X;GmZzX-%Cu&x{CGpk;%e7^F?(qMmh29E(u@YvCvSmzn;_~Uz$3#yRl!jY zk-6;R!BP&~y7w|Lu(*+8?q=Mow_afClsl;?RbVfeZLj4rF3@wSl4K6_Z9E1fPFMBG zsmC9gkb`Ygx?|r-h_iTm?`abj8+pByZ1y{~HqIWzXNBg>(K_e#$)y+$Z@Aoznt`?+ zXRnxIwF-v;&WY#76~TAsTjqON*yhl*)`9{1TMyK&}_=;tMAH7hE(Dyvg(%AE7<9#L2*S zU9>q$a$=lgQuX^K7^}G7hAX=c5`ld$B#A=zsI0T#cP2g_zVTB{nO_EyE@s#W#ZRi; z*iTPZJ_9X6hW4M)9#J{hrSox8yTKx{F~>^+Q;R@@b}w86V`N7xr=E&~x{{_Y+pgKh zEB})?TU_BkFpc$1MY_rhxTc%s5|nLf)i3l^^#Pa~~oKUl@i!>02Sa|Ci&C z=|3*K|MkZS*}9rJ+y8j@0HS8@Rwic362bs+tN#oF#BG0uMa@hcOw9nYX7(1YmP9}K z?;HSmB9{NQ&E=$dsH(1FgwOSOco)ntE?|2nGcX1`G7#Z|DPfsIU`+xI!O7W1lnaU? zBLj;i~DH=0Im6w}}uSolPdEFcxJ&*P5Y*^g5Jg@uYwJ-pY zDG)LMz|%m8GAVZ(LM7%KK7k-S1At3`7`4tSdWEhB1jzs#nBJY^&>zv;aKMru zy=JFp3T46H3JcY$y+Aq&T3EO?1+qELiA*P83Xl1g{(e1P_)Gt9k!F*Ss{r|mbQ*IP8N2izf$>+@rr}|`ii6n z=H)L-#L9E{Ro#d3IgsIWly%buqRzBG5O*sGk;gY;_AxOKnV6qV-`$9p<-S)WCX}*W zOe_lvOKdw{T4H;C-^DNP4|u;jKGHk)zVz_x$w)JpWH48!Elp}EYGHmpzSN2RdH8SM z;cw2{x(7|1@yMfFE?yP4LJ|b#4K+atMnJ(UiNGO4><7IN zBTLc^O0W}!N^&WOHxube0-Ry7g-R1WsNkZ43X9;BTB#INp`t>iMeGF8i)fT2l&;DN zmgtwLtRenE%Zbw#z|XT=0v>5x@wid-0vIGX@;B$x=RM{RPC2mP!ovOxXd3Y{?PY*X zbIURv1C^q?5U>Pb4^104XnIuxuOM86n;C`yyhw?p9} zriasxvF*+7LpY(fdv&Af!#V^%4>jGbzo7W?^}_xF6^P5Dltgufat|>S1~FnO2$~me z7xk3%6eB}fj$9cAB1vzL)D+^C?-s@*?`3%Y{K)uF4riKwXwzP})u`5JVJcw>C6|3HCR3O?FFzk< zd6P~BaMB*sYBZ6WN*W+{agK71bH?is?ojXGalSb^ySKlOyze^VIV7acM|(sEL1RWo zpwU&%P%oz0plL*dMOUEO)(A>{Oa)0@p~hD~SIJUSS9(&ESKF@hRr1mfE!{6q%2zIR zRyUJQEwrwiRHIknD|?G!knt#_{6l-n_lV6#&ZfXtpk1Tgx6$1h=N;jl>s|Fm3LgX^ zLaJUQTcl$muA;W6!J^Tm_0Wr9RVI!|2!6WOF?H>MA9G4T9E*~e~G%KRl zSQ~7gW&iuyjxUBl1fX;iur24Oxg#u~-zWVY25f6+)z8Lh$XJiov*b_f1p5tK_Nx)j{;HFOjaY~IMY4z%evHIl(~wz z%TAu%gJZ{X+v>|XbAWlaF?i})TanI}zE#Ur$G5q;@ldB#Q(ntTTTDky2cD%I?w2^z zK@{7@#=3XWKdTE5_B3{oY*hBXHJlBK4fb_;hE=UuE&V>wcp{gC@VnycC+t+D`1}i~weUG>xLwX_zYX3ynw5Nk3P z1XjpeNLk2+{UYU;U3JD@+z9-NuzB=9&!Ee$^+o z67JYOQ6^*5N3z2kBWa`Zqw6DAk=aom5rFu-<4#A~4ge}Isx`_n$|p)Z83S1;c?-os zQc<$PovCMJcP?6LN_9%0YVcCfQX*@1bB`5^uY9;OP1?I*rH2rY3fwLBX19xm6X-evz^&H+Fe!b$o)VgZ5no2l|H_Q3a%-`JmY%{w0lb{VR22U7&8yABI&%3c` zxxBVkyrjAS#{rvN7AHo~^%{G@@tZ!3zNMylrSM?4{r08Fp{Ng^d(W@%o$SDL%0qic ztxahIX0zbw@+mX!B`$IHb~aFjR^H8H-Mz)n;qfzZ(YmZ^c08AwONKN1m;0XXY{&XT z#Yq`pSP$zW?%dzeX?bLm518*Wy&Is{aq0hRT&Hr=LF=v|Z_v`=eU5XWJ?1ubapi~M zXD6WfF~8!lzT-c1E`B0+k*x)bh87LpKM~Ac`2Wu8<5o z1dSjS8d8x^QbM@bdv%Y;j^9;RPS?|w-Os~m6Cw&h1D6bhwX`B8{}LfiOVjBnI8tsS zoaz~!hFwDQG_s@L0<0R*%&9Cp~v7rO=FRRDpT7%9_$M=;($Mear-5JC@ zzJKHQ)E`xwluPtGU2UA7N1Fz>>khpKFX;|)`j7jEX`4ZtH(x_H1HUNEzdf$8Vz`X$ z?Z4Lk;=8!iwOd^;bIkNSm39zjX8R1uxd?D^JdbvC_{7a^dDvd#kDYA)7I-S;^86&y zf0}N180+;~?BQ7MyU2@Y8Oxh)c%4J~#N7T6eh|y%_;rtQ-6i02k?rtVwyE#Dnb&)G zoc^V|x3%N*_MV0@jf&?*>4u5!`wim9@@e7GeP{*?Al&x)hd$JmrvExz1ySe!ZbR|I z>eGSQ=`?e`-=Kf(S-tsGGrG?_JnNY|++lvr3|c@pVc0JeS9F7}({9wDj^l8R+jA4b zWEDzg)kVaFz}O zv4B6bVz;a;JE)4LQb@MWh$haYsu!GIivwds6-JVnM4e4zN0Vl4(|UY5P6T&|LvU1J zt2NeWyV;6|id<^aNpOZeF8KKI`0%hOGoe%4gORp~w;X0PQJ+KCA}XDr9X35)pHo?p zReBCnFcn6Y^n9|zP9Be|Ewegt*&k+x%WlT`QchrdfZ!k#-g8=yz~)CqN!wY-lw}M>x6Uf2Q-F?Z z#gNLIA~G(_ZbHfuA=MTN2T9P9{qe{Fle^|Bty)naO+p%JZI`O+a-J(G<6n(XVKjE< zH~NsX4Z)?}m83A&=jZ%<=mPE(jKA`>>`$$a5b5}e=N(h24qr37)ZDodGC&U7@w}nOohD>Fa0j3A6hA7qx=9#zRaOUrN~Y0nwgIp zgOvU7gQ60-++JhKRIaYVO}k=BE*F(ky<8?lwa!v33Y4fGw>*4HP(vq4bVKF5Jn;V_{&Oq%WP0v z53va_ev9{5bD{|T>$PXdr4|s#*f@c}30WO3534Ev-^WY#RF`m?_zY zOEr@xnTgX^o6XMuqC}}@q}KnfinAtlmuZ)UN?(rWmGZ~qBhW1kroH<8Rn9^1#6d!` zvF7ekan(Rk!vcyO08uVNod7-I!4@*K!-{>GTMADKn~-*K-G$6avYi@ivR?nwB^yOb zGHcRPx+&3~_Myfi+%w z{O^gt(TD=0!mvg-&n=FB`vch@uZ8!=lL-ZxJWKzWuZjw7q*->1sS;_Y7WY8P7ud2C zL}dZ)y)TmIr32=!smprYWg#a&di|$4dfY3h68qhiOj++VKuD|4kz(WD+2Z4|>b z$!N)A&aGxy7^a{u5UwyRlZN70hLGVrg0=&qTTA6%((= zlrVkCLlkXTuny!b9U>W2o6*rMV|{Y`9Iwhk61#74QRXYPoouS&VxpWQYBr(Xx5N$Z zNnXwF-gb9`p${Wt=kZAY5TkB>1$?mGfc}>Fsn`uI@|?5*bm{%8<(Kk2r9a@7FEZ8h z&b0WtP9Ae=7u~w3+(9V?b8Wi7;-Uj&54&v)#}=KQAj22w&=E?lOQq!qr>(M#PGb-V z+ZzWI7luibbEwyt4@DqPhBV}F=F~zPRh6MiR2Qa}&YJ9-$8{sry^ox%R5y=nk^Y*! z-o+=!7a@kHpPf2eSa9m^texJBigx>~e?qxA$s~_WO9n+CcNyy-kO?F3&J@tuKo9_V z01*t!SiV4*-u}wq<@f3gu*nlMu@S}zF^!Ok3X+L}A{QGVC*SHR#pO2Y4;Po;IvYdf z_`XCv`qX}$j`aD?$}8z^HV+UGJZ92uJ5uRg4LUz5Ws<6}Yyc?98 zz0L9JMz6@X%u~=AMa$Djx}GGaNrJe1=*K0rWE!ESg^qK$t?>{(l^)AAIZY-Mh0Oei zg(=IICNF3Eedd61j``G1e`%A;Twc(hrxTeIV;$ zVkQ|N+v~OkFKZhN3M)zNHYh76bvLHO^YG9&2WY{-1Y|_Z6t5+BBI)V9T<#GUI}`}` z$vJxoL8BYo848Xh+JTFh3j<@6hr1LelyU^XEo`oSW$Ww(cg=NtPT0N9tQ=!l^_MkB zWpw1Dr4$)!!b}-)dEK}=44CN6q8p7HHeHPTEpvClPRLN+XayC(APLYAhR8UfjF$}x zVnutKVc4u0ORdLI@2*sFJI8<>XU#Sb&Qj)5ntrO=^8B7d30<>nx~2Cc{~lIDyJp4= zj-7R^=Rb`bq9@r9@6s5Tvm=8)BmCXlPNXqHG39J4QZC$4hY`s2VY~0gwt9x+oqlGm zS3>GK?9Nh+A_R_}{=>9SwR!Y)Ft*1a`h>84l$pSX6~y6orfV?*Q>KClqV(q7|I>f< zzEzJqtb``fup{O-c(s0E;#>@00!)t>qTjT5xwMg*k5}zQi!e`_42t(+UKQrVsa)Fo zf7%P-?z8ieSRZv&}3LyVX;qn9-fP(7`Vf{^%yDtHVisf zU;jP7h>F^n&ngy&$=OS-UJ$o5xqN2_Wgx159t74?J6Dfqn z^@E>(KjLt2#ExGBt?P?sL_i&?|6+xPAj%q+Lmo>tQapBD5XjlEhL; zbX?zz?K|#IkY@d=UOaoiX(2w*&AFy-*@*zBR;Fy@pi>I|RS$i7P4$dqh_@igVOmfZ z=E(Gd)`p;F09oqauIGur-`(DF{F#5V`;Y^9rdyNB>OKz+alxlp^uocu%C(y9@mUMz z9VEkTw4&6b)>76t^%n9DP^6KXCMNya!gOOOt5mEVY>eLS zC)jhX`&DHWY^q8#n9U|h^f61N*E_j^yJb|Q#&6OjDIGT6aju)`Kfzuwj;(+~Aq`)I zXp2cAs+-pb8qD@uaR<>mqfGr9n+=bXLVL(hPt)P)3$-VER- zy<@;ZTGPuTTdiiL)}sMkBLS@`-5SuZVO1x<0u4ccq}qwzZb{in7BRz+C*t zc=Q&3vrmtkjjSIRhX7ZqZx4~dVJlA2X!(KxxPPzv0G|w7cGxIW^=M_z;AHjief9id zmK@0$furT8c(WoGo-~W{eGSjOx6G91D)G~y;d=knnu@uM?buRQtC&Ckj(zKTD-tv^ zD^%i=`X)|6%cgjEXZMwO_Ov+b<#Rr~g9Btb)OX{=b$x;Z- zYBem_PB{&^bQ0XXJ^&>YZm%7o`ny%dvn}5PrkzWCv8q?pIqMf2m-5FX>n4u!`R2I z^qP&dcgSs|mzg3Zv9(3!Oa5i)l*G@n%SUQWKORZaAyI1U435=KAt>V zvCE5};{bS;=~<}n9YOtjT zC*ZZy()GMv>A#CLsWhhOh|GPCr2;U(Lw_HMh=`)SMsagjI#$m_Z&j_TS&q6)@=QaT zt0KLyBv97xL?{*yesX%NYvHA+4T!zy;vKlrRVOGD z7nvep1nqM0z++5Ax zgV4pl=k`9E;Jr`M1;SVjRu&T;`FiGjFR|MDOTbjQEflzVBFNjqWxmQOX976&51FQB z<%2FLr<<4-=^>ll9p3BL`-8+*dTU(>?F#>|t?^qAvSGdf<(aK%DY<`;Hf($Y2Vcx57#U$KD#{ z&_c>CZK83=8-?Dhp;f+Sto6hwlV6{5b-DHM&x1qmUmgamxMQm8M|vqgVlTgYh!8v? zIm!S=p^=fQ?Dvj1Mm6+@&LNl-<5Qa83OVjwi#PFI>Ev|3G1>B?XB&tZy&{{x6CVq5f z;e#|4lmWGed`i+$_C`om3h1$!zQhxk@yVTSCFHt5;tFNe<@=3yw+{*jse#D`UZadra^C^ zC`<06fl9~8PE|5%UeOC#==Q|;gmAl$nbtRCsIOYS*Y={PpBdyjdUQx2be1>5XQSPnQF8TfVm>Z;wMynfJ zwYpv@3AJ3vd|W|0O+(R7Z+I#m@1bedX$Sq z*Xo^U&@B@3C3a}*k6BAI-zXN2mdT`PE#Yk{0d8ITCu?qNRPdZVr>NW)OW*Wm%d~S$ z!Ve})D4mE$lZXR+5wRgItGE3_J9(;K#eEhRJOiM9k)M!;Q}-yRFqJ^ot^i3J?36uj zp{SgrNn|YaVXM4xMr|lziN3Vb7CjcAD-8)rpM{nKr}TzR%HL6ygp+-rB)>C>G)N9v z?=6Ik;Imu>7vP5X;>#1$Vqs&yiAe9l%Nc_G)&SE=@CqCP)YINU?lg?Qi1Ooz_5ej_ zAid3_z11R){qutzkBdH&lop5k%Uenu}UPn ztO&14H`_&1KwK`=1b<05JX*rq2lo!UgQEX%;GKN{Gnbm40(d?yD&y_u5o5-eR zZ6%i4|ER2H*(jIhAju|NY1Klb)mUX8{Di{~TRYk|f@Lrvt+^A0&P(JW$Z;lKO`}cc@t;q-Kp_%?KYZhBx?@dx#{dOh>=G5)%^(LTGnokW9_I zvLc(=TAy3Xl?4m=3>+jGy`*_@8nSYR!)I+Xz<` zW#1=h=goMazF}HY6Jl2|Gt3?*rPM69=v?|OZJ@HzHe$(o<|c^cY3a_4>SF>nH+0V2 zgZFJf>=^dzYBx$kzG1@uJrt_&6tK}OUW%Z{#wn|5FBa^vL+!#tKUGP*V)HtdD?!S-cB|g8#KpyXY0ilo8_oyx<}BMd_E$)K8RrD62OGWqHiso_6CFZw zZyggo$%tsolO+~*ti^~<6oVxbn#&g37M6=T|HIx}hQ+yUU81-Lm*DPFxVyW%rf`D0 zyC=AN2u>il1ef6M?k>Syb1T_G2K#+;-0XA{`i zhN4l{vjr7m)`Ue9KV^~jK~h1AC@oua*h%U4HJ5zopUhnqv@L3hEq8uM!;jq8E_&{& zTLCv>^Xu~{j!)qoSK9?cCSLs~6z)pzu+`DH#l2pj?J-^@%qPaE&zf%$6T=b0cueAt zUgJY>yZewf<+WO!AFm;7W<4KFPw#;mqyljXMQRt#o=7JHJ1uwA9Soklp*}`_9BL05 zGLxvCZEWl_xOnOACeBvr*Toc}m>=t4R^B24db@!Wqzte84?_@dHC~nvwO9$12(o_| zeEQM+?mS-@8%!GU8?LFuz!i;227^&bv@;N{u{l(P$|AMY?RvBI2wyK>=s|@9PsmMnOsw z4efx@r>8r9<*W)LUvtrrm$N|u#Gis~)EG)?U{e6Z!c|z_9hv(h=4s}O_}taJeSf0X zpY0H)&^vL;%&JX-YI$nC**F%mE{`{SvvHuj2`I#yM#`Vy1~G{|Kjm$;RO@{?-}ukU zkB>#nx|J}vTsF6TVxQ)u#Tv2Q&YqrUI#Ax+Y`w?Pc5hRp@V1@4#a)+t7XqLVYG?kr zoY*0V$~kqGSSV**6!j4+E9$#eLK!84jXFxm8&A+VbZJWGvg;7?(||vwZMbhU@%4)W z-FeIq9P)i(^l^iU9^4QWYn!DJ4>w)W1_z~fqEM@Oa;fy2oKTM5#f<%d@Sm~0NjrgU zqOT9~&wY)Ry7!1em9H*##MKUAZ^fsgQG=yco!L-Q$YxmM$1~?zeSkX z{t3j0IGg+`h|b9cf{cI;(q_LP91xbo0uZwVI;okt(ENcn0c1d+k0J;H`UMYJfxsYf zfCC5?@&o}xE+Aa#FXRcJ1wxV3K$w#&2qjVnp-DO**vT9OHc5j3sXu@!5XfY14nmHs z0m=Xg5Qg+m
    N{RwGV(t=1=e+-QI7u(9hnS}FqwRF*61>G6hxj0D}S$NnoiO@xL^)!xv#JbC?R?LJ`a4NasuTP7P^S08t)b_?5eTv`KY~6}J zk@`62uWch4*z1N*dpP24hU~8iV~Q;wKQvq#39w^}BCHt|v8DKe!j^elpo(r}4&e>8G~{DO$0jKPOXM;&QU8t8y={QYD3kus_nEQ}g(#@}n+hES_q z<_5`86n*hdA)m@?mC2gYzzwYd{OLWB4~0=zsOHq17yCtL2&&uuekSf7^QJ^HOFJse zXb-;%+N;mcPMS#a=Y>ykGMwmu!5cc9yRv22cHMK4C_tE^_9We?Dk#xiwG=^DBCXep zs^q1j5jpZf5hia~ea*D5b?t{C)q`^csbP*dp)WS3>=wjwX+P9-5 zx~?eLA~j0{Yts!g;7nj`2k|hkQW6=R7nO~XML($1s0ExoI1G%Ztnq&7w)Wa~%ogos zJr>U$Em5S~OWF^@%|>xI=2%?&IKR4VA1eQDoWO4>+=1C6nmsap3+!AqV?DstRh^Y1 z)?v4AE1j{h3$}LQ&6H{NIHGOhfo1km@SGDjq0uVIx?4Xv=@0tslLI|}2LYn0bQHdf ziLt#{x>s>tY1l&&!h&FzIONMp62%3(M$yIOhPsyHU)Qgat})1e`&s`@h*k`wGYk5% z(kP2d%7f5pCT1pPT9EdG3(yqk0t8(Q{?uCdhXex4-$W(;^IU19Ar0v;2!aXweiD{?X*$y0^9cmlh6xo9n;WgWdqS zXZyn#m4)7ofe&`g;(jCcNhMPPRbM z@&g?lKzA?TFO~-YG_AkJsGz_rZg1lHYb9mG1;|`otxS12%z(yhJmy@CoZOtOjO;*D zZblw%7B)r>PE#&(Zf*`UQ**PwwU@DTb^(HjCjV$}%+3J>ny|AlvT?JqFtT%-n=KvT}m%yWHkn+@`QKw7>Tl2|s97E>eoi&wE@~$2#|R&nwpsdU2R;* z1hqvaB$$lt?XCF%zjmgL)t@eYKl{rEKj2?F_|=`sAJ>Y%b*N_M_^%xbI-3JsTD>F@Vq|6l6+ceno;z<*ZY zKP&K`75L8z{AUIJvjPbJJXC;0+61WGe;pYR5dQ6{=a-(_pC{bEeq@3UIKR#_s(+79 z{7vIc#Lmv%#aWN-4|O>Mz%LcO-x_eLe^=3C{Uc!Vzonx0hpgS-RP_GPzyqlM&s6k& z59iOBh}t`unmPTJ?qfFi74>nUk>X@xVc}upVFsP#RLx9W^jLXVm{{3KSUEYEm|02K zxmcNaxJg(+XChWm^&cm<-?RSPiu@kZpWXde%6$J+}>4+5*UioU5?rAL-Sp)Jdi@yo@_OGZm{kTgzVvL#h?h_LLsQ3WTB4_lKz_O<9np8 zk(gv|PRLLt7C(A=)SShuF?#m;NXy!CvD#nkzAhlJOU0_R?5?4_OI6_S6W?d0oIwT% zqTo>KcNam|q>|oJedRk_g9g6c-7D>qP)#d7ZV_sYZNQCrr9zagyxJzYddx13{^b1$ zc`j!J<-3DjOM6aO?a#B~j<#hA4OA*mQ%(tj9y6@WVqzA9C@ZdS6P`bBCYMI-JAS?g zaYcpPT29a0Rx;Q9S^bHZhPyKSqi$_py$*Gc?YHQnwsS94h2A&;wn8matADV{27TGF z9nwh1Btr-ex_cW2+)N2Wy-ML->#u?Tq&d)bqj_4d6-osdCW&RSwba&;*(p+#O@Fjn zk2bFpgx})0_TN(QQ}$S$$kaTIae7)2IJRdy`MQW)SKr-|72Pq|MlV3ywzMw3W?KMT z-QU=^nP9ii;S4BW*rTwiheVz7$f9Q>yOFj+$Oi2#gy@0?YW2L$8H0Q^?_mTD4O$1(-Br^W#q@^!(0nGsapoE3cy5GMO=J(Bg*G2ufs%gdeTWzBEHwnXyn@%YKTd@1#{qO$G-Vd-k;!-_#l62y1w%7M5X))i}AZ*(9DHFpXN5FTBt0#|-UHlTdH>d7aSmtGL!f{XPc zc)U|wr#lQzq^eDPZz>;FbQlBYI3SEs1UCEjbkcXWrH;b3oOr}>1H5dx?Q`eUCn(xE z&#Dr71cV{`yb2+H%c90 zvj)RIY4tkK_7V%H%1W3nf;ihAIejKH%J!`hL-3nSp{t`S1$Cu3YIj8nszd!gx2)0z zLA~J;8F9VdE|Y%FO%IbHplm;nRP7)WXoA}HaMi-co5qhf-4S#|=lD5UdI-+nnMkoK z=Q$GH{rkii4>oRTfMrHJMLsbf_*pxj+s}Fi8-E@_jM3{wYT62Pk?J(8rgZST zu|6Y~MU25OJUO{3S~c6!6GN$~Xa|I40I8kNR;`zHQq2Nr#(ks;eVyd|p*`z5WLR%} zLQDyuzW2owpIX=t2SXqW~!Ee&rnJ>x!HKc#2V(meY z50Ob75juat-V4bJE2ppd$`5eU$4l!hB2yN|8{mFJQnZuq1$D@QoT{udrCmB4>+R|O zZD3t&c;|-c6n^8LX*#v2DBeoseGWxGdO9+a8@S=J-`A(eR%iB)<6>g$;rWq69iAMn zOw@aA&TU|5Us%rZwjz_h*hDpWK||Lf#oeSDp2g&orN1Vt)am^g1`hSUL6<-YLci%= zc?W47Qc*}kI|e94Fer6Z#B*fFu<#SwZj~=t1x`04vjaCSa#&aVh9^`!_}03hkvE`> zH^NZR1&QtaK443)ylJhPw--Po%hs=B2|F)fCY1!w{IXj&_Z8wgMF)4c^^_kS{6|c#bq#&CZGD+g ztN&$)nr~lJ9(zET{4G&x)kP<5&d6Q}B@aHS*JXs1t#8a0;d9O+{`F*Yb`oF|F|AC$ zyC^!U%s3T`%OWJ6O_WP!grq+i69SfaQ0pxd`R5Zo8uK;#ho9PxrP1stQGOCk7eGE8 zmEEivj@LvA-Lwt;&fxD#ripiKL;L=xBqgq}T0Bmi8=mu9tDY0N1L`ayj5Mftre(b~SL+Xe5Sn2{{5RcgXf}2|SC4z7U zgbuzsqH{lcIKLWV>D-v_Zl}-L9S;M&DsK{3=Z#vxG0M~)m3{`gOC7fleB6rVceg4W zajtS+r&L_7&9tsjA;W^-eoB!9)eZwYZ&W^|mlvL~@MZE`klL`wi_XzAQk05b6F~o( z>ZzL+Qj}N$E%10#3*Z!kNoC2s&hUJPkez=~IMuyGzF+E?>|+&VS5ym3XUgzKV+jg_ z&nKOPAjJ?Djm6|uXyf1YXiEQV#k8Nij((H+xQjKf5vzfw`MA0=>k6#Vbn263ddFD2 zgON(Jz|?=FMLc^%a!nKxcu1O@`^>qS*8yIy?wX1e*i^S}y0vt3o5!lpGrLk3L#Oqn znphSds{fUwWcJCj1-C(#-fee zufsm|_r+t+(s(|Bm6V*bTpo)By@2uJ?$@h&5j0p~b z=6h=&nI6$T$O!mSh3{PFWo-;QyejHVwwm^Za9-4=RSWTx&*o}1oz z%9ODn?L#Hm)(5d)=~r9vPL&5f9z20)^Wl>~D#2IG*zH~Ec2~Vd5po%E%=MUYZbvfM z?C})DZkRS%b&50bROZa%>stT4Si5iN`(aSZ$uJ8rQG~BrAU)DFrDS2 z;?4vKvyiiM+WQ4ZMOI99n$?)p;DW@+SOWIOthajbgr5V@HrB_viS~7_qZMh?EXPo! zY7Vr#T5_J0lN{@t3^Y{)Q`7172U9lgJ*^7@RzJ#Ds6-0R(Vx6H>_x__wthwn6TddO z7Li;Jp4RJ98A2+xa1C)``-a%xKEfGNdBh!Dp{LG5k6E=l;aoUgldd&gzCaWibzM^G zlq862Q*i6NBwk@BM&bbkb> zj!`;*PH*B3e~Gi(xisN(VzQ*%`kSdl2?(lKQkl?c>fF7=7~VwU1x>3(wy|~YCKYX) z8&`qhHT1J!Y1S@_!S_%I=7yAeh5_=SjQJmgV}^MarDz7P3j^yBc71O<_E$rvTIHM^ zIkJB2l5$@Huwj*Omm)_d#$?BW(x;SweNnTlzlXQ1WLSur66m#NXVA#*q1B}DI%l9wLhM(RoU(dPLkOX_n~-lz6G3R4> zRQsW)xpb4RfcrLaO%ZsE0jO!TGHp*VP6aL zY=hfOfE?1lX1_x4+%xlC(QZwezRQgUoO9uaOxP9Pjd5m=uWewT{Q{MRwzJp^o{W4u z!Bj_9)(wegC7et8O0E55Z`P3IfZD7oI|5V;T6@uuEco@5X80~Qhi%O&UHbpk?7sl-(pEM+0|?v~h6-Q?5JSDPd% z`&)~B^WiUoKY`qNJ(NXIS3*Yj6d4D**P3S>WHThem0p#Ax@e3zbAigaZ~S~&u(d6H z{-f(K4%_}b4RPbuJ0)vo)LEwMIuFoVLPOLccm^vTx-<{NN~v4ks?7^3IL&+;+PCC~ zC5cgV@=bSeLkPS0HlN=ID`7VX%|UGTVRQjRS_UBByuLjSsZxcU?7Etpk9@%g_C zaIyZ4mh?MP^()}@uaTb5T1%SGlhl|1A!$|*&JQi-Ae-aZc*JgB=?Y1S+eeblc$#J9Jx?SZo>T{+- zZ^;+~YC27cElU~M$m2gqFJAcd`CZJFekn3t90Thj5oYd8BWo%9Qg-b0rCI1@Zz$u& zCv0-64$#E>u$&2+q0WL$5#5cY41>u7A}4qqO7pXYI;RTB-mp(R|ami9IP98blh(i zHx|jLU1>C)w%=`MKO9HMNp-ZhA) zTH8*Ou(CLmWTu*`@tI%7%~%%2lZpQcxT_#!)8e5*!F0478L=;e{Z(FH(ja!;HDv#= z0{_B&`Dj?M2%ZA1ji}fTGTm~mFDg9KC^W-JF^tkVB`M9KK;6KLXf8)5-UM&NWj}g- zf?z5$6347=xxYf%hMnPs8-X;F%2hKPwWb!`nzZh6+i89EKH1712Ay2t!-3#fM3hq6 z(SF$c$PRWo1|y@*)>NzJ7dPzjQV%&BI!rZ*;|28U?}81k;`+ihgbH%%PrctR{Q4_X zzE|Ny%A{+kji4`kF5Bj#yBE0PF@7j&LK!KI)GoXhx=*+J$|p{4D`7+o~oFDC!Bb^>d_Wx z2F>{X0}h8To7}UF$0yad`7v#gIPVkYM4@3le}?qP_PwRVT1dBTwX_82O7G^~Rl61^ zC2eM-@^8yA0fC%DA`9tORA0+oYGQ&cIwf*iXW~&tI8o@9#CC#A(Sfhw4m~y>a&w{& zm?Fw%+?r?D9D`vXQauNYr%EZBX}@Gub%yBp_nTfFU|$WBi-^X}~?{0SzGRP0bfP3dg@lyiQLN1}{c9#jcZ!wbm=lg7|Ql^XP74p`q@ zn(Mxh#S_dT6ihtX7-)Wl!-)!t)(%2)su_=Z8vg)P^ z$>$8`i0{~C!_<4aE~3lAj=}jXA|Hm9c*aagT^FZ9L*DMUhQyHh_Q^nJwr(2jNw%vp z?|G1QJSIn-&}t}mlk0_p^Y<}d_{n^d{l@r=9yT5m1J2BZyrqowK=lm1b1e`qPs+a< zpRMIE!T_I7Geib&IvFh9aDOk;Tojh^U8!Kffv+IGh`!T39eH-YS`-oph`Q89Hbz|aw0y8zshWXF zevzYB@lc%#P+Aj~RA2H?NKb4wRFh8Lllx;)`!XFfMP8PNqdTf;)FxSq6 zMKi&Ki_i~|K~21r{sR6G0496?-m2l!HfjE3sY8U@$P{XZ(zd7W7@g3T!en&98`rKc zTMDTnKL&TTuOyxqw}Ca}IG7jTz2?-*(4Dk}K*dZi@bzB0877`_HnzYl-rsY? zH??%L2>TSDz=fF(SUs+8WrYP=F7*(W%&ytql_$rDT3(>SOS*ITdcaprBnT#8DW|>0 zVNJx%f8E%Y&a)BRd0WZytfH8*L@HgmTX`$SM*S`;@M-bS)x8EHrE!xx zY5{Hnv3bOeQ%?j1+a%BqW6;bQ<{u#hGGSGa(j_z&g}{iiLrQb_lC9@BGFn+2U_{41 zTq^}Cts@ffz&Q|@^rJfhGG;!0#dRUsy&1pn-EFiV+1<^|l~3L;zt7~u(d7DZ+0QKo zIE-dz_Oeq+JM)(vaetN%aLbZ!S+;F1WQWE)H|ClYIY(FNUvLWPCD1%WvXhfAITOW+ z?*`;oe5jk88Uj<_c`5L}gOKfS*{niyV6S4%l-hwNt)97p`5atgBmoFWYqb=Vg-*t) zyG7}tjQZSq?WF%m6GVe?7byLLP}vd4`-(2n24Q$P6}s^(O4z{rBam9tuQC1#>m3eq z_DhezXRTOxr^{X;UaAuIcAZ_9UKVHHxM}cjk$ zq4A}^444$6H11yHA>u=OBFp;aUkMCr5nI4?w;@B7c4oA=@qgx~>~w+=PPc(m>$1J!H%C>8hI6AE>Z$HDw|as(sQ4SalQP+HSRt@{@sgB?Ye0gMnh`Ogt4n*@iZ6S|;L(@-Q`#=?&QZ=oycN864mFqvWfFMV zJXNRDnaF$<%x!!;yC>K z0lEH%I#+TeT`RaJW`_f%k`T_0+QVwc3x2i6sf2^=q}+h@ zLrvs`v_4zy9$5SepO3aYR6QP0CKS&D_=i;ea-oK?ew z5HF~ng_f4uEJjlJ+Hz~?B{NmlPv2qXu1q}ZBFDq9Qb+E-Q=C?OnC={WtNu9SelL>^ z+lICX5ggYXa2!?Llc&$mN>CoJ!+)R`NPdL;=veCC;_VwigmH@9)zcJ9Swzd2vhkjQ zMkC8A`_n37XK>iqVx2TU{LdfRS1k>nT8VXJFv;Z3hj^y;d`eP>{D@GVXe+YBM7SVl z%F`-Q699zn(XJ08|e2Gp?vv&u1*CpDEKfGJ| zuG>pVC;0v|;ewks61YLt$%1ip<4e-HbyH`jfl`R>TAN7W)s)%xhpok7vk`7W@Jg)= zIV%9sy#u79+FhKI`vU)71VN9`vHuvjC}HAqhUQWR&r-&vnhA3QNGHr@vcUzIWCZUv z7Cbt9{3iC|($K4<^{`>{oC`ksWRTx;+L=JRM&yT>m*RdI^$+lVNXK4iLlonFhY>m` z?|j(Lu%|&ZaFf*`FO&?|&yxq%5A_*K9m?gw-*#(+YJFM0K|aiIoi#FCRy z9#_vxqd%nHdqK+s_QVsN%|-4*%#9>mD@egq z#mXu-c=@Dw%pQ3FZ{hh0@zMdzjQl^X?$j5no}~4Qeqx7b7s28-iMi~SX#l!~wI=1M zr=Um<_O>;8lUEy-ndw(}KTKkLOU!y;|J1du=_MZHl%xJxgEBCqmCEC;oX{dO@ygPw zzFyms$g2LxEYeAK$Gb~19 z*Mtw>;|0a+>2o{2=3bEmQYUa|~aCYIlOd*1CiErxPRpXoY4YUjv!Ej=qrMlpJ}utOo|w;%JER4SbkRtd;$ zn?pKmq!VZ27|$xk>~bXVP?EHq%emZWF41-LI7;)&5e_Ke#UJgK2v2-hfnYG|V5Sw( z&h#5JMihjQDwNih!do{qrlD3Hl<)76FAM2E?k7jQ5k_MSp1>Agww-3| z^}_A%#F14c?DXKOcerKX122QNyG`yC!$F85?{>`s=_ zU77$WMlFI0(Vs7Rs;Vu1+5B;Bt2K{#b-$aA{mOJwQQ#9yr zoUi{n*^Hf=mFs_q1|@9w#rvLBmPiTPb{`{_}7x%w+?~rz z*&M_!dZwhkB4L!z*%ir3bM?mP0a^ud)9s9V`eTHA9v$&=#>lvtj=ob^KgoF6)sI$K ze>gU>)0B}MpPDY?N65>I0+oj+`fxsiVC2MqUwb#*(roB^zbT}E8@A_LYu{cO9{jKw zyZ7Yh%`>+L5cB2qZ)RU!GLkTRD4$D=_~WPR%Nf^th5f6WiGqpU(8P|4WkNYK zy)D32oFHQM>k* zhf2>ZlGtx=bV#BZ7*R$M=8uIeiFjc~$v^u>2(l%QBi;O5!~Tgx9vO~f@5vp8V&b&7 z*pey`o@nv&$Lh^1U1abKzO@_o5o-dISZzmSFimu+)`gw*Y+HU^Qt^EFlFhM!D^JW` zq7l?w+4BP5W0U(uEy=}EAX8t?XOXQ0n8itI15S5;PK`zmcfZZmhj@!;jXlD9cz%Gu zYi7 zm0zC|njb@R4qqagxz)T6rJH?%=pzGkpPSc!3+p$i$M7@X%}6cgu%ML;11F88)4Ms z?LiDz*{8a^Ro*Ag&o70?jd{1b=mifkWD29NSQl8;Ft?D-) z7?j>nVXE$wx$j?5eNj5rG(2fnP!l&!NgZzUcV1>&y0x4{|0vC7Af7>06QMMFA=(1_ z9lB1+5ss~m`U;A+UwFrMV1!3g`HcdsTL0QwKWCynN)-nOd+`TNLT9LiHd^kZYQbXz z8-dkD(z&+U$udSf)hBXQ6x(hzlf724x1xPSpLR%>aL+E9Tiz_yQYT%f2^QXE+!joC zNvg#ZK4h-8S8DJsi&vmxmG2wcE=UZaLo2skRa(ZM3 z=4xXd?Q2=F52JU|1hcu4M?Ct=5$p638_5$}ntU8Di1nY*cOl3a#+g3c4}VIn9u^w5 zOfp;-cdY88sms#&&RnO)Eyr#Ts+5^a9I%W8D=xlwlS)qD`D89z?J28O!TU2hNmZPr zau_y%$?=fYr9@}cVQozj^tu=dW#WI@nYy;Dchu(jSP}RpKCaA@?@nd?{TD{`5rhmJrf^dTuY@9gxn1 zToXjl=a@dAsNNO_@ADJ*GKn(sIDr)Q8q8HUyPkPFb-6_+1a7R0hYif#DF78yywM zNCOu+xB|OGW4dVw;Owa3`BohBWV=cevQ3MtRKuCBqt}&ULqF6jkv87oq=z+J-aF$l zHY2DKkb6}w>q-d^iVO@F}+xO6xQn~pwYI)N;u@N!dg z4I{`Hke{A{YS=5qMQK%QF>GZjmIn@k$GI}#?#c{EO`nLs=sA@MoiC8WjN$|zrA0Db zyn3g7ITtKvIqi_)?3-`lyTUp+*1Er#oHk!Ma_{rIre$3gNs+peRu!JH?y%@k>yM@G z@2HHuk@PVf%;=eIAi}%3)P=jAvx(nD?c1(hqhZgrve?L|Jb8Z+c_%eit2`Vnapz+VKWs_m7QSpUdywZPy?X7Bl_~NFg4?6OY(CE! zFyr*)(qEcBK+Od^bTTC5Est_`Wk`pm+d# zR@4V)pxBNuN5&tj`A(lONI!pK_^C~=A$aP$pkG# z7FWbw(1C#{hl(;FOMoJeDQD02{;HPwdJ_eK>s`POPVwW4<;SlZ>x_sDhw#?a<_F8F z_i5trKJe@Il`T#&sk?(wOq@AnqG|`bBO$2`&G`1CC_>drjFku%1>WDPUk7cNoOYvV z;)_WD#8r{|`?$6qE1?&nskKV8k|b56*AcWu&rmezKBRFt?pa=MyxdNAS%7A}W#GI0+Wk0YZbcm>gB zRL$9|h;F0w%84C;}aicY*%6F1m903O9hUtt#DKy>1tsBGVXc{2;$G#IN5q3Q#{U z3Oj43Ph*`ZEHkH>fe}@&|y0A>lOkLG&mF{nD2FHPgG^ zFGEDnh7)Pz)bC2BQ;)|CK~VXZyCf^nHvSOu~LvY4b0 zqGYEAGnW-sS@-6^JIqSLqgcO+Uq+vIJ@vh@8)6~4vLVZd5-FKG@gQt3GG{LctQtHQ z`cw)gR5$`ZNw6LaCz;`-6= zfGK1P12kR}uZyIc!KTr@@`mLl&g*pwyUmO5xlA~y$%e7a-Oi`*SCCeh@J>FQZZ~|g zer;r_<0)wLp%+W+snZx-p1mn6pv>xPAuhXuo6=wb7uqcQkT<_X^nziZR7H3jF zJ&Cf-n{!zgBHB7x+!KlxzJ&5?ewJh%g9?B|2PXe&R_6UJbz2do!A(?9gyR(yu(Njk!BZ`sIA=&d#_%<{8N`H+I4;kx-svn#eD1-}yZh95CJLcAk}tSYmHMS{LZWXi&w939vGM>{g(9o6T7$I2zIp3k)Qcs-+ zK&sPiQv4=7e%Daav-3>?qc9Yk*jE8P?mVxFnK63y35Bi*la@g{WwK@JCL&U6&mIRT z&jMsSeD@&h*XjBuXj1t4OTIOC`?oBmHonBFAO23?31291^=7;}CSMY8lM=1J4JqcM zH*x8rer!AR*pE!2wVX^j!+3{WpkvAaLvXnpDlALI?kEKlDX2`e_|4s#j1s$s-F$;ndM>}2z7lr_nSleD zK0msA!g@;lQPKTXGi`>;v_Z6U?$lF@Y)fK~ldQ2J^P^4HqjE9}ZG<9mTQ@Hj=l7m2 zi$e*p{s$5q+}RTYDN*Z(l7v(tlnd2j8Mv~E=`r>=$j!`Sb?yd;=G6rX!NVITO!)B-41x!hrvFvx@Jkx~{T$_$c%tXmVMnX_w5g*3 z#erO6&yOd`FIz>@5DSb%G>F{{nd{!tR8O>%uRS-TL;HC6Sr^?m&0cBNjeJI)DEV^( zXEOKaiHZD^wb!wV%Y-h7cwpyL{BBbLaM z5fM2?Wsb<2eZRJkUNgsb{WbFV2u_RSeH+ayRe0}j?Dgt0bxH}`N`I0Ukr&gqXe59D%YH4Y=V zwHZ2`BjC6ywTWj7t_yfqy(dWcxOB_*hdxjV==;aq*)>%638I$#I7)GYXy83>Pwd}4 zm(8C!^=9;V3$+;}UMzE5-iCauY$gJ~FD1sSvTv2gI8+`w*Y9GO!|R&wuNIuH%T&5i zaZCExSGv9ASH#TsNiWdLD9HdLEm@_V+azT8t$q_=haQY-QeO@P&9E`n2Vf~d_Lrh&t&@!_*Ou=zuf&AYSf>@N~=|Tw6fWF zN_>Oe4~QJ6e;2Pkk|l#EK*wnK7HfX77CL^QnUbPY2EgJVNbjCkIk0_wRq)2j z^A?2})>k44&^p(;e7E|Pw0zBrAu-?c#{F_FES~zeg5Og~|KY5UFajppxD2ryfEPM{S97t+!i0mgvJh zMOLe-{}4TD)C=#&He@CfKCh&{&%Qe0Zl8Ow3}Ekplf@VGMF7 zdrQ0z>2J8I2hbVglYUoY%gKH14j=^z6;frSY?cFmm}b)CP^jjYEmZ}Y1y=MlmsDXr ze<(q4_9Z;`hkgrIDrg}1Z{vi2%Xj=8C;SyR{1?_3+b=;C)&E0rLbhKLf&UF_?6=MT z=Lv_ur}bwq|C87t2hYDS#Xt#%3EKnFzLk{&Qcn53o7r3KqaNmjwbe0)4%YKA4rh=b z3n=Vl3M3138U4dL7COOMWn^aCVm{Ewn3_XG_UwWU5Wn94N;=#v9vw!>RInqfU2IPh zNzaUXJ*Q;+NTQedJLxcUTP`l75I(_!@#k1eDhX2lip^2#giQrtjX2D2`Gjfz{ZZK3 z`t$lQ-KZ7Qs3DdkYUS{Pjo+RO%ec-(Y7q77=+m*1ZOh~R{<=IUEVyqs|58eLw>SP1 z_{z?nDrWuaZ8N?Xn_6M@qM;w=NRVWBR4k(S^QZgOr`B-oThxqIIqU*Q^)!BzInQ|7 z(Vi*!By)oMGJg5snJ4c1vbuuaim#ubtj}!1)+XdCiG}my`|}TXE*4{JbIww;yXY^a%&xNLgFS*Bclq^VNnT{?ZqphP} zG?hQzyCPDPqDR*ymhacUdX)}o^)k5GtLK>C9E}yr6V5Y@oDvhFI~b0JQt{XmH#uZn zh-h^qXz?r7e=LjI$4xUCOZD*bb%9!ObNhaO=n2`NHwIPQncT!yRAOg;JmP=xLhM`+7e-A^9Lb%f9g&IPWe zRGg|Y1JhapeW_+?s*bG;Kj-=@G3AerIRjudaQqd#%rM zUZh|;Q4FK?lTZFu;E=z!qcVk=c^mp3jayN8N>Al-+r+6?kyQxgb^%t-z=2l96Q%bE zUu3Fea7a#*Ge#-RDYrTaJyt24{fq-ujOy+n_An(8BIBJOA8~&D2B-c5uJ*v(O&?rd zIh&ON4Y^R24uN+&*)>txb)k6yxS2NB7aUo6Hh3PZfd@Vq_ zqrm0cLiQO~NnK6>Pij;)WU`}~%XY8zOvIuFvW}5UMz9s#ik}zMgy1oL_*1je-WZjv z7usknN?6P5@>QJDSX!O1o;zc0U_#G&fv%a{KGy!kC+U2S(9juvNvplaqTNt2rqwDM z7_&Nb)1S-#M(tj{+JbJk(Nqd*X^w%?okig3O0I~K{4<#NO)Zp6J4xZ56T_5f_-_W4 z6(eM(I5;EzyWVmQQ>89C`_L18mIb~eAYN$L2-L7{6 zv7v-0NPd5LkG7X~XsaIAtB*B0f7LCiCZBi)H%IE`3Y0#6M|KYRVWI0jfk13WG;m|= zXEAO(N(q@+7T7q~q*-xY0{g_$e4b{zbljlv;j)eRhC+GZ>aoNI#Jn1s`q|!Jd-O%g zw>T>uLLLboE*X3Ug4<8E=@?_yu2_v<_m4=|OrjT?gy9pG{;hFP1lj6o zi;zrG^Tq`8G!)ToT1zkvyp1e&|nn)6o zP~I9bKAuNqyZw_9IVq1n0!;B7uR}{Jsb8MWM$}ddoQ^LWINOV|TSmo4ACU%8P zem!YM@Q!kbo%S93^`5371E;{5l5Yfn8r`5w+eWk2o9Pe8$GQTH6vxSH6Z6cU6?!4w z$CJiAq9O5C?uoKl@JrATEwRDb9?poz14sztaMW@JV5j1wz9G;@D>3E}9IQ&VF5Hx$ zb<@=ecQ4b+$nYWMv$YxP_@Wk*r^7kezn^_?&F!dx)6w;N>OWBw{bH41z&M0L9`lN! zB7Y89=QyGK=CrW4n^L`OI=DmAr7i@u4V$Wf@3NteyIWo6z z=qqpjG%|=5>@sy76Y~Fx0dFvP>_6ZQu#F9lJOBq|Ndfl?*utl)i!N;c>V|aQXD~1G z3&R8VbD16^YLQ9_t)y=5$>_=B-rBo#T$b{@WvP3giJ=FK>6voERZv8wBrV zPitGuOQ(o#b`-q>2z{7Y=5VOS)3{J-*$fzkGl*fI)-gCJvBd*u!p~-TRHgR$Gyev> zRQlYRV~i9)5K7>W1jST1_Dn{YrtTnfIKTH?R9qP8pFbNrX(#ldS-2&mofu|tUmQnr#2w4yRwlQbm+ zFv|f2r2(asW1QQ04rz`YLugXsjRJx*pSg&8-vT zoHkCXwtc}sy8GUVx9d-JBbLH$h?l#SvM`ekpiMY7oEq*?wb zF@8O;M4Z`(kaW9SkIMT){ELYK&}a(FH<~;t=^c9ygG`~8#?itmS~IVYsvo>bblKQ` zIwz^lDdzPgDH3v87P<1U3LxHu+__9giX%{ zRVX5&GUa_QBfXpPYSnI=41?;OR8MS3LVlce5TzKd45oh(6TB%InUv;5hKqFf*LTkHaBq)} zrxUQc?Cu-2fc`ToQnanhElx3!stno*_CpQ%fts6!w3En9*ek?0h_xuFyZ2IXbm}Y`bS{7cTAZ6o>8^t57 zI7X)+pwRO&5vAScXE21&^vMJBTlNQ(ih@}X=GpedPhCv{6BPHlTw)7MTYOgt$vUlv z6{+&G;s^sG>nHuhVMo(Wg_xIm?zEs5*vkR-=vknYI(F&4>mg{jp{SwhI#3#Lrxs~8gN$x(|8Oc4$46UVROi>MpnR5x9Js*}sG4J29i|bpfWU>^8 z(bld`bODFHxRh6KX0r5>6e~5ox{FT!fO1y$R}M&Q$!i0knf^MgU*>?%WgwNKxI6rl5q!P$4 zZd7G8KQ}&phs2@3Evesa=@1o5cv@UQr%eAT=}z6b(~&S3>vo+17qs6SR5-t9mh8sr zVH}qNwXq?c>hgOZoAt}@d$2Snxn!)6w$6g}SJ?JI3tJZsGXJGBb^-BF%%!6-(7x)t zX+w>@Bp=$zmuae|(}^>(!gG4CKpC_m?AqxXxb$x4!%2KyB(rBm13uqAKGJWCGe<9OXj|)Bt=Li7-@@|w9E^ia zZsCk`aDa58a<+)OD(aK|8t_3JdKc1W;cE0fN`^TM{8>3Zd*V9Me2`oQ zyBo##6&Guk#v$L1-(ym*el0pe_|=!8^GJLC$|1Q3*(y~O&2%n>20=PY+$3C|{uF>r zU>O`^iey^g5-(DznNdB#5;fA%hw;0uaFetmaQS-Xi^A2j;rS=~FP6^Lfo~mRQzTUd zM-p)p-e^^3?pPreH_X7?9L$JFlqFH*^L7Ca&W_rv87@pZv!@oU7U4gX<*Gx-rcO|UW5l%%;B#*Q^CBta?1@Pe1qtb*jTM%U} z-k?QIgR={K1a^F0unVOkMon<|rmpu!cX419P6g$X-RfFBWgixBUC$t@zU5;c;`sJ~Aua#Ai`yA>5_l(W3Fx;v)pJHG%F~k- ztuKasMsT8(+?73LrQ`CgjL~b=0Gqo-zzIY2m2P}QH)537wvW%*cJf@ssjCK6U^lx{ z3O6HNU6tKYZ?8TjBC0x5nbszSymy%%C ze3kdU0vBua5K-nupfT2$6tSP`@hkak=d@PX*_#YRf4;W-UFFbKKB}m96?np>+L`>D z>B+OKXHH2TFeEf49(hmx=FQ!|Uo{e(4p&d_I9jL-lc<6zuw8G9;^IB`xsPW| zFKLyHq{5GxUENV$WG55z3aIma+g85SXOj3HIcl|x#K(FK&g>j5bu6y=?6vKxod}D2 zK1t12CqM`3Je<*wst@Ol)!B6BVo)ADImK|o*_4CV538o@qPv^aPPVy{=O-b;s@q;i zP6at{#g{U&pR!;wHMOwg{Ydgg4hFD7!Y%JV#svJ-hn$=Q^jhovq3i=X_X4W&cC-#qS_D{C*U;TB={~nP1-$`3C|6928f6~qVB>?*WkH7ApBmU1C8ap$?fA-hu z#$AXx`sC@)#}zRbynPuO=(EXTu>0eUGDqR`{l#{blg<+-XeD5K{1Nm2++8ZKuytf{ z>K3fiAZcqOj<9xBS69#BQXRJYevD7wc7GWi?X)8xkWNY;z0yTxEsi)N@EgyfqOwv> zQB6KNzH`SkbuccVsXm(ZaKjvSP|6&A(zV8~b?fIx_-fhIow-_q_j!H2*ruXC)AaOI zEmqWGFZcMwM=W+X3!z8H|0I2V;n(VXKRfYbmBr1v>C}A*`YWZK__6WBW&P!J@yGq; zbUB}~vFQ}cW|t_U9vb4O2qOO(J?J$+EWadT>+EEzn5GnqF0y?Uh1^`4j3gra@8zT@*}9Vjz|bU zu@Iv{NZX-wPE0~k=VpUV`ver~^2lKb%OQ~*ft(POQ8?#z!(!(_+XSz@9O~jtRj-dE zmB{4*_cB=C*80;UHQ+Js3!&ujS_45OSk)d@rQ^B!)4w+FV<==S4S7Be>gtJmbezq% z2PQqPLei3)N@2vC?5MA+aeA(~Qw;24w%`_#|B#Usthd_s zdK7LB8)>W%Y{BxzGh$UYq{qkjuCO5b!+Am&l(y@Pp>)(8?~+=Ys2W>-!fh!N%d4H4 z;6Ny39!$)V_^vSz*={AG>JAgR(pU=}XC_a3a}w9|U?jOAH=8TX$t@3=?kwn!9H+=Hl`?$1!vwOaIQO3mI(*7Yu zE2(b`C1jAp0)y^mlJ`KPp>9lzF$GPv-Ns%7digNh2D8&T)W6xm4RLh*t87@ zz+NBmM?eWOTLw8(Lc$~}P*U9W6&@%UHQ@~%=^;_PC(>y5!J7%u8TKYdy|H%zvScw; z@u1f7&s%2_OcNwnDTw>n2tH9>&FA3hxumkLgItT8X%H|S0za~z=87Ub=* zw2BmgJ^}otD8X{%Typ3h)^S`3eY`wXH9po#HwE;fXLEc^d1IMW2vr;<>1>SSKL#z4 zif7u~QqT+ukIaB^Tt$;cVd53I_SH1WVZ1asA;fH@$v*pec)=b6ARQzK>DpA>2+q z8Z}W)DU0tPLH@M%!|T8gn`7PsKuEqh;H9{5HFmPxh2@hiH;BsxY7$Dmz8Ose$4VbF zG0q_^8%6yJhS~2i9s$=03jrVenzQkn!&6>?7k%tw7%@5wbR?J2vHdrJnXPVn{TA6I zfa_sVl-I*Z$8dSy8RlebUrdd;%rJX@_uVlXA=+ zRx>vtTGmgs!^OEYOS;!GArM366i6Du&-vnm0ilESX5QaOT8mZ;ZTDUNnzf?7#b^F? z6>oz)Sf}X3;6q8{HyAG8qS7<%4v+5M81ApY6A9tH((xDq&7dl)6*KIr;khsd_*n6r zqTN$WLaJl(*WV7>gj1)pYk%xzJM?;KEA`TH5<~Pn2}4KnHv=ynMCutE*t?E7s2Y8$W*S_d zSLyIffl6px^{1(Znd!I-x?d75{p+)OaCBqIit^IqmC(qI-45|qs6rtB0}t3rwA+-1 z@;XZ%0em{OL{^GtBT0&4xiMU15X=FQUTzl+y-hn2i}Oad=TA+|ZI0>7H?(0 z_`~b%)LE=={Kk@tvAXJX3QrPxp0ndZ3ZUQns@mlnVi}F1IA-_@<5}D)!yLaJ3&IU; zIgv}5!clZ=OZ&CmKf@DJ{Pt5s6b92N0=*ofZ8KZC4>Wif2{^o51f)bdK82DbqG^=v^{yx35a`+oq1`3%#~J^NjH+hI zHl=;fRjT!^CfbtJ`mWeKf*9{xAOe7@Lc^lPfVs~|4yl0hF!RFld_V-LsVp8@g~3hw zX9Teyk2-?sOlE%jx)%e7dOB~7PZ#X~49#GE5~M;|WTMh0Z(49bKkWCq6Rr>-M4|{$ z!vtN^ep$PkLk7beb`W=FGQ8Z4gRlKTD$}{9vvlVtj=mwcBVwTNYRktoVGS#g7gq4m zK0lS{;9@`idXXFwmIF_Snxf$E1@xJwQVY7-EZSXy*v4~>_^iy1)@PM!AB|dibCW9( z&5*CbQ6RjBkp zvHQ^zkq1c#T`-^1Mr)z&8YP&w_J&DOYMU}OPKWD4C2|r8ck9)LPYPIVB3SJlSlmMU z7*F_vE=L*QxQ4|2p$+*|j&KaEZMB{4#Fn}ZfH0FqVFKF~zEi9_hI$3n)v7}&X#HDn zf#eX6i7WL}ZJ?2G(={L!2s>pU6swY%>4qLmLnqo`XUk5NoLi2WG&7z8N1fU6!2PA; z#qGmBBVAq$BU;{3tNfEN>qw%F3PsY)N!G0P>f&|V`e1p$lBZm@iR4xv%-jJQ^?hi_ zLV7O}G-WAxYzp+r5y@WvEAu&15@y@L4#AAA%TC{&=g1TXJ}e*(L^5}lhWie^NCml$ z;2oVi<#eGcECA2{vi)K+LgA;TfjaS_k?bg=ReZ&QGJA$BdrL5H7N>RU^fzH|UgPDn z4MAW_K?eUmGqTNY-kMAH7)ie%EOC&BBjQt#bV^i-4hs#>b7^F$_@#VxF(J>VyH$lB&*S|CSTBo&L0PliCA(Q(hrlXwP$a47jS|SLd)AK*zmLJrf^D8ZdGTB zVPSlG$7Yg^KFN*7E!~q+6@Iy<6f(C8PrrQ_v%D6*b!W4#w6%=}_2^p|#pR)p(Ac=* z0SC}%QyRkcen@`q?wli0YtZl#_!j5uQc}KdC!ZpCP**+5m7{26iA6kvkERER^#-kY zS$|qEh;8M8Ygja$fkmYKg;ecQ`|Tznn}>2;{y`3jBakL=P}*RjTAvO2bDQ#|O?#~f zj7>)_a|I2<2HwdQ<^vOXu5mYl(L*;W$+jN2p|`&jfRcZiAZ#l2l1dvko$M-wvBAyvzp*?XspriMWczT znzKWsdz6ixx5CHLywcb&FO<6pNLQa){~&}YXUrL17m^rD2~E_LFIl!r|Lqr=frjj) z?tZFhM&zN4&)RE)G8R-IYMb8`8sW0k*F>qv3o>VRvYOVb?F$GbSztMB{s!66@B$wC z^DO`G9*CSq9Cdr6Sktby)Fewm7t?Ys?u__#sE~|@I2CuVf)j0t$yP^NeIm&0Ncnxt ziZZb@?^L+$>6_iZWr%FHYSoYw>^lA(0{|H^5AkhZ;OA4mXHYm{jgM~^S zTd7^|_?>s$*;N}mXM8lx$8CZkSxsu9#EuAW0%Og5KZ1+t((0bRAUWgAC_Lg3n`_ZU zIzLJ8Qm*f^!S|YzW4$(kBN1)+1=7Fl0jUabaLC_is-wlR!QK|^lm4An`Z+TGURA(u z4b2}bZS1U$yT22coBj<(- zxf!s+uU&Fb=xxsgs6A$C0>CeiL^hRRNnxFPOGji8|FO|y@jV)5^95d;olJ(a1%F(0 zJ5UnqEkx43!-QdQcN!?IiMgp&iE3pF{-K!Ls|Qk{Ay(}FPU`+DsQuv=zh-t$|0|fn zBj!XfFB2C{ujr@40>+|2lPzF+)&bGv*|Z&Qy)WjV4bwnJUlJS@r|*MKrsZhiX5H@i zl09P4)H6vrb@;JCcT$@(Fj#o3Rzuq01jd+Zc>*1$xT zysL3MBqWeiXy9=eSPOT!?0k#mGjVt_LmpEu;6h-d2Nm+{*UOFbckACSw8uevi2qW? z`xjo=KQi7wqTPRz@%}y8`oARO{o}6t?_;ve|B~GOznAg;68ZmIP#W{UgmM4R_BTd0 zW|n`I?t;}fV>j85{({nO6~O?aOS&JaEH?2VQAPDp7!>dMDVEw1q@1Z+As+-^ySW)e z&1o!@AXTIZ**|hQoy_j#RjBOcIY=QUx+& zrT{?kn3t7z1`)AEsP>_XZyG_VswkqWc)VkNoKqr}U6Ozh#ev8MSveAg&1VL5?zo8!&yTM7U6w=v?|xL3#KQzU92&CX>ZiFpC#W%yi@_Zw zaJAJ^ua3)1r--HsT}LXAL|;aN@;kb3=t3}zQ|NpHl>3tG&#$>LQ4HLf4HXlw(^FyO z&uZb%W^LBE$mz8=UmicT>AGRb^hB(IArZ;MC8{C2Y*oHwM`+R{1uSs$sDAtBlEP+k z)^(5T(61tDLX3J-&|9jKM4sXhDyfb;b`Lc3-NSiht(AJJ2A+y>l;SK9Ha-Jo$vz1x zB18WV3ChYl_ay-+3GBnST(yAHI&zDIF^DtC1U|n@ruFTkvW|e2gdWSwFC`}cT-0yp z%MG(@u~yT>rp&P+)#vyX&;Ew^Ijp{qAUu^_xal6_OqG5;ocl$n5~wMssC!P7)_WkD z=|zJT&Rj)gI#_mTx^-qpO};}Wm+PbjqK7yHS(#?!&p>jWFC$jnPjAyOT0ImFfNP#$ zWv2TO4#Xce*eB-^e?oyzCFA9l!%7 zC?d)i%?m?t5DrU4j(nOyLFL|5X7%RXk~x1V>A}#ji6R4}h-2rNJvi6SJ@4?`FK18;f@SO@RW-%2GFOL)GgScJYoSq!F!p6!G$u53FggIz0Ns0sg_#G^elY z+mv~?uTJAY8D;85VI+aM>kKrFe4P^7gmJI#C znHTRM;BBI5fRX|f-P($H8vTH9_J{{_D_nZn9g;Zd`0T9$^B{+$rpIv@ChcYniyAag zg}-3_W`g}}G0AqVmc$%&|664`52ncHi!L#goq7WyTC$PrIgg6lR0wPn?Jq0u|M4&U#PpY5o1_N zgdfu4XYjL76EGLnq=K4dkk# z6WD-1Uk-EgL}o2>%*Hs@3{6@9J`O9%y(|W%gxPmfcAqJPKuQ!vVgKYOPM2qzCSTeX ztwv6{BJG2Iwc7tQRYKDRfC^540=ov5V(Dqnb8#+c|4pY~8Dz&_@X+Be0j9gIS&eKV zhTE5&`oJI%y;)GP@D<#XvrIbLv)w7)ofF)kU!AWHA2XU-?<6>9au?FOBH` z=;ZnD8hDuh#WeqaKcfG?a83U?;{SNl#>Bz$pWW&jn~9rZ2tKRokH&5jChomFBR}n| zTG`mOy~?GY1B6>hYABV6$`xh*5Px@a2qYz%S+A;48CTF-u-MxJJ+|)p!7cx#*lgSO zY}+!US6taDznhkTyvOk;(mW`qn70#DU-z-TL&+?kNI=C!praz{?OWf5HQ7-v7T)S;zXr)M>L{;qgWGudjCB4yxUp}3+YGGH=fM4m zWKJQ?$U~2}H-Qd81#gWnTXtmkB@}$|4ZT(r1KR_#zX8#GLeCnPRhca=6JsiTW3VNu_g{DdGsvN+5?>&0mA=G(bA;_& zEhE1o65!ip3w?%ufq)86mokqo+`T#Poc__?@>TWTFRQswL9%=zsJd4F^CPl_X&-rwqb568qzDP5(}mhW7w4%?Wg7ys%m8iG`6n*tMk>wn@^c zFE;8sMw0lQW3`5DbE%WE?)2c;iU$@~B6}trmVr2dHFsq3Kp*`+Lr(|2%XJiN!Vv>c zxioj&+p$&V9FYr+isLFCPZ+6;6cg3-XH35{0qys2bm^hPl8Tu`h z{0&@}Q^<{=iGufdA2ycJG%}maW9btOOp?aOxt);`_VDq#WPRio6gvK%!Nv2`j6#Yx z+@zwxpjH>X;@(P>!bOQcpnz}Vn8imUXq8K_+tCS7(jGPBs+5z|*GT7Y4$2a--MXt& z9wviVj4Alj82-5yG@`1;O-bZN`SSmEK(dU^sSiQNJtijd{tEPaK;kN{Fmf@guE4FjJZX0R`Sy@MWlc}DFagP9_qP1E5x%8>-VAj|R4XK1HgiELU)k8%2A;0C!0_DVjL zAwK~%sH>+Eh6mPQ;VmI%Utv5g1eY1DrV=koFwI9gO1U6YCs2seQ2iy0!(CCTQRLHy zqyO~PJOG`U46#N{a0tYQ8TrVgV3S_cmlpSoMO7B#K*^TIj$?wR;QXr_^;_dO`Bq#iI&zMyuf5*ZG_0x| z`GUzl)v|TCXXH+@2Soy4^~XYKgre+Z?jAYyiL{=`NqR)?n1B@&*jmVfutd^XSmPIZ z)0=avk_nPmpaxH?{E*vcDECA%qkl_G z2$+TOTJDK2S!IKyQIZZQQ70S6Kg1Kj87MeP${C%6On5BpTCBC0U_3KwHzu89k(@UFebmv z1VjDFgKP3J@0Oy8ju%x6V(`*#ch7hmh`+RQ}PqwINZ=|nrl>* ztWJzCw3_A8HY+x1<@Oz*JP|>b&MssMCxj-R?&I*3+&Mt56;yvyY2Hp$%9!x*!q6io zolvt&cgG{k{s|ec@rnk?N>$ZQX!iUX^E^srAm@TE^Gnf6@Ml~2uM`uprn*|-K~~!w z41Nb_VM{aGuCUz3W0VT(2nA^dbcTFB$>qions*As5yRSohXM(}ubzK6K0mo7^R)MDuc&qbuKi}PD zE>Z6yfP36`wAySEw=sQ@6(4 z9TW);XnTHksTtSNNAI3NzN{MEL2B5V9oR`Pi$4{`w$bgjB9p`8i73e8x)XQ8Gzz@5 z^v~y8tuCzNQNux9VfHNmwsPz@T_>x-f}dN0QRWUW4M9$E#LKp;D?-zsj;e82ppj}9 z_+bfM2S&0UH?3L!#?1>U<3IbawhfklOS}HZkM=*?#y_4$lqCY8KN%wcI1*_2{O#SN9j&ie8=G55)?YxihF;(7Zd894(u{YjOK0b^O{av6 zVe%tufLiI`!0!)ISOR7-nKUzf0iDvx9KmRdcIUU=p93@GBRxH^a!r$8n8)CHJ%vvLmhCdB zAFGoknq59GBWOK#*BdS$9Y5HPx9N{v^a)yH-hNsj9IqN{vtI*f2t(94>T$fvlODtr z=+T}6$EY1wUDqluD|o?WLbZ!=01dA1ePw=#C0j~? zzYkhQsSi6L8KH5b6qJb3W?Zd@-Mp|M(+a>KZ3py@+fr2J3)EKv9p7VUq;?ZaMaJ+8 zhGz;Kf8aFFhyuu*ec_g(0dyCI?A&WvA)C#jniB{u1F72`tV=3`h26G^ihyqm@AFq&Au zGXUCPOH=IETE5Z0Ziv()Kc>xnkjVx;bxHZ$S+a6hptHYnfl}C+L2<=^{o_UZVDJfl zH<%!-+J~+R1=E3NhWRMRgdNO8%Qm0A+w}T68v`{S{20O}2QFd+kqXyNTKtn>Ov7NQ zb>WM7r%eGh3?r1KcU00uD6^h+u!h^w&tpA=V$;mX+eto1ocx!KwmWwqXi);yPZ}ta z0#ANR+&Yxha849a5ME$m?}W9$OpqY$h#C*%GhG==lAsM0)ia2%KOwB`S~yP*9S<;P zV9b(B$)H8j1I^;^7s+Q}w3LyS=^!^m0M6s+8y%)zAl!J@P*jw=T$i;_;o690Y>pnoPbRo35FzMufp($o>MWa& zVoo0Hbk@Jcpn638BC@#xiK*x$Yj&H4%*1tO+_V z!kzp2t!~mr!Tr)k@Dr0c5Wc9~s8iqwIS(!6?W*z?c6JW%Eq?({)6gVq60KgYedUC2|J zToQtX?JyhR*q}*5_i@s^B86#}hnu^ngk5QH{NQJ$Hw{T=eyOUYb!F&sHYRJ!=5 zVA6v%hq45R@^@4rLOTsurdrF<_UA?taxo$PIfB-PK8=Pf<<6G&8`4YZns*s$f6C`y z30m2T!;}G_!oWjpH2cYh(C zKfyImb5B@#GxJH+EHpcQh|0}wgR%xTF@VJHC7DnXVX;E#u!=V(k%tCkJv+ij!d+)^ z(g&w^C`}sMl5zG0P>8r;fM`q!-S{40^?nRG=Kf9w1h+uPs)$tdim;CbVV^4Zp#*BP zsk=ibdTE(4IigJuV{ynfg;@Abk zI??3v0~N^co+c7&_e_Th7gsIE8x-qciO+uUe%z^iAv5jXl=L1KvS$-%BczXO(bylI@iWY zA8&mQTm<0+N~#m1cg185b^=8mFTSWK9elel1_a^d*eA_Plc8XDnweh_4Pv$$IhzG? z5r9vtb6`M19j2|8&M7wuUc@Aa;FR~wCmyB&0Y!-KvEvs~m#Q(m_K>7+4wRr3s^C6i zaV=T}0V9R>dv6jF?&gF{!pJ%yqU0KibP{3wWzc{_Hs79Xmd`=SsF}lvOW%EJ-%6`Z z;f@}&u_<<8bChN;~=m{=|a|w?`=}xY=$;Sf9AplXXggdR#X%7Y50a}#b=nO>2gAMtj*aOOVZSAWd!<$vg{ZL-Gy} zlGfh=H*Ma+0|El=QvP847zcF;^`!`*kRu2qbsVKn^7^q78{dC@@4R!#^*M)QFOP&K zB+^b=sG6_59Mz0;PrJ%`U8_eCmp#BEZ+Hm1&xp>VuRM{+7l?zF*|D3U1-;keO=7#{ zD(r*=GP}Nf3xwIF3YlWvOH^c7?ru`b1Jq`eTZ z20HdjZUPi-mLdoGcE~GG2QrIiyT9e8yoDu3Zrt*SKceq}e<81UN)nTCcIu20p#FkF z#*4Utuu|8SBDRZY{g`Xoi8qB7k!F1Pq=O(nL66gqBCbmdF8_rbwccjsaXP)T`IeeF zFaLGx@rOLhRJqj8ZhZHI_$iILn}k`~vi>uo{9RMZG?P`;a#Suat~$MHAGojd>Ocpe zS#{%}FYPUQ_pTusr|cW>9@`R&vZ<~jqi5ik{U zMhD2bp}3VA4BhWc6q@T;;7DmkFj)&H>SfE}v+>dfB--Jru?D59kARoo`nwjr(ZA#Y z&wkGb-z1TT%&d0=hS{8)`+Dz4jTeQ^@JLuzVVS8?&gPqtXUXJk|7m&a@DgUT@LAjYo1c9Kx{KTC;~5=3pY&Y8P3-vp;q4uR zbZZ+W&C)L0wr$(CZCCBGZQHhO+qSXGwmrMQuP5d`5vR|@be!q`PsEC6{kT_T-kDcc zEa7f&u+q69jHvN?FQ6>FDiN1cn7HQJfu$Mz)9OwKRFMGW$ zqITJd6OVU1L1g{9QjEQuZ?8tn>|y-fA+mibOZ~?)wQF#;q{sXnVF-UvmDQ3o(FAPn z=Y=~JARhe#IQ#duqNP&}o#lC^kX~~!w(_XHdXpqkeVI!hum2|whrdhvaZ>TCS23{k2Nhio4*ICT zleUeeDckpMGhJRu0!ue>;;S%XECnJc#szjT7njJH9`S(o+(@!VNkJ~EB1^o&^h1iw zDKUAZ@VhG#y4O^SB2{vZK^~wE)P_^2t~f-fB4t~f%GAj?TH|A}UFy9pdTyz=>C39Cm$*U|@r~fAFDF;N#)(sw@c`*O z@`N-9MDdsjn1eq)7nOhaCu4cW4dC(V_2VzaRMgbGpH6+AwtcJCW!Us;f9qDSw%40_ zyDEvO*c!ecgfdeV60(Wt3QJh7jAoLDQz4PmB>5g(lSUk*Wwf}7Q#JPVzR{@1I`iQS zsvxZAWtPxt7b_q@cc*t6as8==p4p4|o>hA7ed7DAS{|uLXsQ|(sdfU;P{+s-~zQ zlp2P2mPB3&UdGDS{NEbTv>o&NlHx3J+D6Y=(~E2yK|cFQg-9N)9!Lf_R`Yt@r8fQ2 zbW6^$iC9dav_T>FY3^ z=i#7+H0d(&Y_@z$1NEb4Q+%j#!;JzCVukdQ%$BtdAj_2)IO)^+<^X9;QHVr;A3ZJk z@{FgiYzRlyGYj^IgnRwXh@s5Y0AJCvw1g6#de4Inxm(0)TTvj(>3n}ZNjy*5#O`-zh?aR%Giajd?5>& zV$s~NTaFA{`pe1l7Hd}t;LpWJM`nMmdHI5ORq;6C74wVdg@f)!gt>u53M#0A(5*Gf zV#?)k0a$n&esM8Hems9mJj-i;7tBr3dAaw_& zO}`q)saW*V<-o^d5B>S68JSI!(@sSg>hLb;)Yqj@d=<&7A}LXe#5Yl~vOx>th;azL za~_H8LHL0z-gyx49#;?y#d~{5K(qjz01X(UWu@eSr7*ep66bSt#G!Iu=v$ECnSdwq zck#?Y&eqBt7dMdR7n9mA`-BR*!PjmjwPeF?ll!LFrnY;7mc`NaZjO?dT=t~aIPlC- zbZUo8uSQuZVTI_JjudP1_dk9 z_=Bi}Tt-NXW11kvihk)|v3!xvCBxV>l)-v~n}4CcZ`(T#bApkC#Bg4J^ULX{Tw*YB zs55^^OY`T>BZaWsf`fhSAIBRQPd*&?IMzl3!#M~HCek_DJUSyY&lI#tCq}laTs5W( z7Px`5$f3euNtSfQ32Q84oacR4v+reP(*wYUC3||3fxA7>$f*3{>xChDl66lyULNKe z-r3f=(d;>|zvB=PpWQr9W*P^90=6j6>tZ4D-PdfhKF1WU5aMejRexv(h4Zz|qjl-44l@ z6H?v0cO_1_|IIq(u4GuRM?(Akdp)roTdp*!n9EP6^zPd7lJ8yg-|TqMyc0@E}cZg+}mn$=A5|C5u7GJAw%;nYi^(9uobg|5%l|!^|0C660|aD0Zcxh z9RXCGK|cJw;rvhH5P(m=2>z`Q3}ncY!0xy{{72+VXU3^=B(G%((xSF}`vtA8GQ>V6 zIX;&OG{N?%uxX;(>WI>VQF3<*TEUXlbN7bec~0IHzIoPrdf#U-0gKO$G1_bMq7yoU zR9YD_g@@_RxeyzlHrF$;2BEqLI%q3yq5?TSZN+}u3@Dey((j=ns`xa?1CY^FT5d(@ zI6F)AiBg`|n$u05y}~)SKVD*>!0o>x&MVzn7bHsu~`gsI1`GYShU;fe3y zap~Y~Q3fbvbKq|jO=mOOCx}7DwC&_Vu87D!-!Dr5jGLh@@x_y1fj8w3GQlUB*j(6j zM#`oYVu`kP&i?4Rzr^WUxfsbMf1*N9LwRq!iN9<+8W?WWIA8aPBc~<9hOOqhQ z9bvS*W57ytjos{dFiP+Qv4b7$kC~tmFVBU2M~K<>qLmzfk!0@&f8zrA^?|P4ENPak zYsId<=*lMx-X}US`%dAnArByj-&F^hAx@-%lN*dcvU&RDwKxF?%wvUt8ZFh4-t;1A z>Bw{GO7g2tSE|&t8C{bfXzf!U=3=ujCuB&baW>wx3!Nl5)8rE*w#_-BgJF5wTC_=T z&vNPtN_~%vNr&$a*D__wNz%5*{#mlvc11k9BvDge_$x+8 zAS%8kq0^%_U{`%#%cT4`Q6y@4pcUrs=8IP)@juigx8~Lw6c5Ky7D&MikwNRVrd!mK zo=G%;9;HwElE}&ki}}>AotKO@B-pYZJs(pMf+#!wFd&BLX3~mxpKhkT8^k-m^M70; z49Wle1*x8?OM%OV%ms);AS>wHMu_QWCpy?LEnw6tzp$t1gzB;MBzfKUnT0ibb}dyX zX9gmJkEqKnuEgnS6i6IsjWmQ#UQln>SNOUxnG?2>nTc1c_|MM}X;37#dQ8`M^RHW`$~q7txyaw zhvGGfcG8)@U}mEeA^GZ_WXZB^8I?HNhG#x;md`2f!#bYU6}#1pR~vQ0@Zfr$nW`X# z+%Vj>C6~#17t!AZshwT*#dNFy_!G&*WAcw-1d%5r&xc905;ATIO0;;yqoQdlk7HEJ zSM<3Gb_a@SA^a<8VJvIsg3iobx}bsqd%S@^QHqeG+md`2Cx*h|@I)56F3$Ok z<}o!JiQSG2r*?Ww=2Ns)D7dUJJHs}kj^G>G9Pgvg7 zWGR*Jl>dEoR!+s5lFb3(;>=z$PIIBF)SuQCCA|62Byi z#p2=4%oTZE*9z;pv15|Rjp46I)bQTNx=eY4h2CQ#V%Yikcl3Ejh_p)PhGq={TZl*H zeKtVbV?Fyp`OxTcWZx{5J<_-IL}`6f=D_oD4-!O3VnLCin5%07p=INr9?xAV-DFDN zW>mRp@bvE_fbhceW{sUb$&b_umpe3L*o{B^9jWyWgwg{!VYT{(p1I#=HJ?3s6Y=Hi zz&9qW>byM)@gGXzFi)!oq4Ps>fDc>%uTfsHex(*xX)|@i-fk;$J4;ZCyV26r@_(TT zvI(PsOw8npjd(@$lTVG?O$R5QD~j=pWZN^u6M?7F5glPWsYsTcDDsXzq~QoQMS%u6j@CtkZ@5XWY;>T~Ai9G4haNk&e3|x1z+Q4hPTkzbMHKscNLKWXA{HKmO9t|wmgQ9fZWlO1K;ucK8X)1 zsSz)wLA#{Pt<>*WOdK)U(*3Fkl_iM6f?JV!Q34nP=$_i~y0e;lKMWCcu=u>#d+;P{ z1<%hxeiDq4TsJ?iehWnd79j0~td#<_zj%Gw29kp6*u#TT?N<$Lgk3-4I$Xl zVBaJSc4dyrH7dv;cycNx3^g=Ir*CJL#2Lh*M9ffI6@fE2)%Rb_a>g*Jm@joah+3;k z-)y21g)j2W(|wHV@3>2?n$Y~NGv>h>x9u!hyQGQCtolXhy;BVdaUWt6;+5{4QT4}glSj)j- zL5hjm%LE{entcdxLf}B8et{b)jA#*o%N4K94?(oZH|LW{B}S8$I@?Lg@g(!-@;D5?%#yGY)}~zETvp z1bAwbrx34`7WeY<>O@Mt$ZW96Ke_kCgQf0Yrw+$AlXD5_3O=WV5yE{U$dAnMDq9P$ zD5VY*VJ9i7`Ri;Jkp+ms&X6TY-DA}5)xxF`=4ojtXcH`<;9OE!hs^1khtDEyYNTs6 z6DlfbZQ4ECX`*uv?tlLJH(c42IRB}C^N&i{zxMvL6+*Z9yho(oT znh~XZ*;E14q(ty@6ih-B#J%L68g5^>dP4+0v>4J*XDoMcn-F{uzIDYZF3Iw#?zOa) zQ+a#teUdw@%M=~cHyxyX)z#8kb8%5)59f>IJ0|d_c6k?dQWy*(sobOnSSLxdx`)U= z1BC7jA8q`{&1&ktG!st+BjmjExaLhiq`Kp+@_lY~G+Ut;`Z&*rowfNcwF9~tR+8>1 z5&uC@H7M9p!@TSo)gtbcTulQNStExtyIu)1a^~lCk~|1Z@%IrKi4Sa#Y&WD@JwR0> z#uu`sC^h)x)wOc5Eu4??A5FdG3rlnj=dxQtT+-lWBn}n@-c==j@<(KUQXYm+P#Ff| z#*+H8Pm_qqq9gLqY`h^|A&({CH&im-^+uI%#s|u8&)xnj3lP3FG0tB|j#)3nJo#7R z4jLjsN=!@~kYtIC7JU1qtXB2y_?Z&i)+@J5TgRuyj>4>|Gshzu8+WtyjUyg#*2EAu zU+BJP+vo#gus9DtFXz?C%ex;4_rpx8Q{%0ezQdP^R=}*EAItl@k>V_t3L%tIM9IeB zKjhHxk6?|jPm<2++Pdce_Gu!R3X=iuq0u_&_VtBgaG{sa&UqIz{l2{nBFT;K3w5Y%XN{fuX^2np{X zOsqVh{6c&{twcWMB&-FmBe*{YN0a%xj83pz+X#kRF#2hl(JMDh#hT&HU2bDo3T`g1`eVT-f$WFRBh+*^l1GDe z-fFds`rYyZo{vjkDz2;^B&z|OcFazJ$Kw0OKHRHD4)oqOa*6CTOOibGfSnf@3v%fSV0i-RJu#enQfO4+tltP>^;BOZD>*ZA<3s}p<21NW2cCAm*#4!3xgOc)Nwcn$B4(D{6ff2wFI7j3Ll;qf`htAm35Qd#b~~I zfqwfwZ#@wqi}tV36jpjmD>PNsy#Ep1*0i>AaW-Ojklnua_!E%#cYGpZ=!jFW(zfzC zzJ~1V>>XOQa{IlFh>ji>P8rZ?iZ~7r{WidbEL&d&+gQUu3g)?QiC;xOsLy2YY6iUC z5~OOR+K#<2CS|(b(dRO%@21nIm+TvCUrtUUUY{ia z8Tc+#i-{K5fZ2HEirH8!quui3`v3y=+U$b5VoFuG0yE#Dr9$Ra1M2uvn*i^5OH) zkmpT(Q*cw&>dc;;dfcB#a!bFAsND$6_tDmt_Z`qf=Z-3h8WN!`YXJ@{eK>>byhCZj zzHRD5e{3HeMcw(?&MR*>2!QlRH%0J#hxa%%4-0tpk_dvbYo+Iy6~v!^$+d+5npmk2 zx8rJC^&m;^l3B%@Fj-uQI*q#QIw%2sgV^J6Y{vTc{J`dY4t(^QeyL$7qE-0=r1_Yx zBcr#W(S#(c69Vz=+!~RD%?l%8Y{sJQYd^jC*c#0s(1Upj%B)7dWo&1?2BM;-*O-qM*(uYL`wfaTs0<|{La6C+Bt_*B(&$r*r0 za+UXDqU6Rr&OY_=m6!_XJAwe-w?lcx&}n+(r2~ybX>==l%RPn)M;Xz$ZMZ2LN_dX6 zNX~K^y6DJy*8q2544cw}41i&Ad3-UMBfmv#8|>@`SIFc!)(OW==f;elz} zxsbI#bZ4apl9hn6yx1Ji*xD@!2o4AY!WQ(=?Q zBOBkWxtIL{9%-d=_QhoV#C-uJogKRmvvW~~MfMr;7zRju!ZZV-0H2R7%}PQ45n3{e9|py;z@*+8{yeiyJTKkImnn_;VErpZfZh=y zArI9DEo;p_f5+$T(sXQlHYq0L7-&0VlU&ZU5fk7M61-w4a&=hgszK3J7^mCh!LdH`^dlwcz< z+>moFj!ypAUz#2aNVfZ%hNC1dS}2z_PcfNfr7K>cbIeXn$`=aI?PDwi9VL;iFM(~^ zm&;jKB=qZ2hNs@oHN`oVwu7C>$Cjp%A!CQ@2fK8rgS)Cc2jLSnM+vW;d`Tz&-Rc@v zfSRmrQ!mZh^O`W#Kf$%oWEfh|pwHyOjL#z9JT}kO5n`P-)lY=K$L45`GMm~={<_WT z;*HF|9y8HeBTKeEM9FYn635u#7SOMl4Af(sOU_D8VJ=YSBZ!_InO>xi80`}e%GYDV zpKdn!1;-t^y0env1c8-m>%rt<1kn^4h6QmHxVM%ePy+YJNoj_xhn?&WTTqQx z=BYX29%pb=Xx1Bwn00T6 zL4Z(OSEB=9lD@op6xZr@RRCUHtARQ=Hnl7eC99K+4k&h11*tE-{(9NPaSGw? zp_f#7V~WL!CynzpF7~#Q#>*0;3~vQj7lqmz7;S+R49QHmiwa#CTtPF{0NX?_pj$ro z)Ugd&xE0pE*ppL#>$&7;+ABF6_C&0=QS5T^s9NNenFd!6u*4)?-{E9T$G4|sL8^eO zPS2yBe0v(d(7Z#Y)?}E{;ENcC5Ol>E_};g&%FHlR7`wxQ*$&dh9DeMIN>6=>gs%LZ zA0D&+1l+!n%hwylRhOWWQV$+Ni&_MeEl}bur+tpCxxZJ4X0UxB?C0=PCsMqvu%wzp0W0* zjLry73V88VF>ECL6cR#Ax(3qh98G5a<|ossjBkrX?_7x=C4Ev?N|O6UsTmg(Cz(pu zeiE5!Da0Nh6b|Xohv-hXDdYY1gn)1Q@$eyEzKC)BZO9upb*To2 zRF`6Smv__SVCC*TvUfA^Nqj;`n`Rjiy-uElGqn-im7GcvMgt8F%4baGbwbsP@9sd9 zp8~-7RW|(j-cf+BCz!GOT_gU_Cm8a{Qc$m64}yt;tYfRN`lyg^{HUdSvHTLn$y@;W z--$_7wI#n3DG5X9w*f-0bW zGttQMKSbjH)0bf8_?JZdr)XsPcg5jPJ=Vz;7+<8NmNBNIn_CYFDXk^PsV@n66B z|Gh8qufO#_pYp#JiVXBjtpB{|cT)Mk0V-2O>B5jA3avoir-U{OKo$|zK*;Kk0xjlr z2wIHPoHO6vCxq)*))B)KN#fI4j>l7{S0BAhYciFcE>A5sQe%1BH5pA5{eST2v=vHK zAXGGp+XJ8LBpny|Gd4A8OSdUmM*ggXpw{?5H+aZjm1C6z%2qHd8Ds>=YHOC;`=P`7 z6m@E5I|r$<$H?(()^M&SCBaLz3!6x?)U+TX1Jxj91!E< z8Tk5rYkxWG371Re8}M>6=b61WqMpfGF-J?IG7=tFhEkxB!^*;xtYVZmA+5QsjtZ)w zIzvl6`70{Dzo}y^ZdJm}*%CzomLbFd3?~aL`>+j-bsKpPai54+dzNgJZsWLI$;a;~ zykwAE!T{b*_%dvbY5xW)fPAteJ<>ow^oOae0ad>Dx5TcXfY*{lxB?Fe1;b7mQEes;`qcg>thOv2V#6q}5P_!s^ zim)v;VOx`zqVY&MyL_bd4udRU+!#;1H{)2!a5c0V2vLTb91OFgEs(bax{Z00%(E|T92x= zxnBPV1TZ*(jVSGDzgCb)$X*lZwJ4Kg$oK<+datS+qEFR~k$HNdPhyJD4+8uv@me-F zY9%QX=J((%lSS=r5b69CL-X;9#m+$|pjQJC0_ z5Gu(bLZab-7Ppkr2OF^kMUhgAt*`>8$wg~~ne;B?y*1wTW$|Ks0_evCJVSjs1E!1M z7dK+EJn9G7nJk43V?P)((~rBp^7a;NOTv#aw*lBI^}+~Pr!HV_K$9JmC0FzMEFYRH#SIou9BmGH(H}&g3QrJkg9&Sz$oG)&>= zer;XPttGVxZ){gc+!8J!kIvYh(-0CPdyJcW>*aN{y*GW=Ot!DGJy-F**x+LE&bMui z9NZ|!(`;4S#XS#(A}fiC?nhyjE~KXSntxbdu2s`qKCd7rGE!DGji<#A3%?g6QLvs= zyxLyoTGmdkpXe9JK(QRyU-+o4_j@T0-xoH?U~F;FB;njbw` z+3S{#IZts-7QG+(n_4`Pn2FZ!@ljvo_2SA@i3N(qS*jH-I!5}Bpm{?&7Yoz_qN3`} zYK@76Gh%WMJs(N>!~*q1gnDB+zbae^LZ|YD-Lq>~+9~0Lb&4lZ7|JaGY)2k3Y-o5CMqotkTn2_1F=?TUY=?yTVa%B{dcsjoCSGjV%6Q1u7qHG30}z*Fs-%0 zhIAW-0rY!(AWPP)0!>k5Pw@#l^^JD>0welp!q=Jq$b`l{!dG$0+5cL-=a!K!68mK_ zcnX=Ln>YanXY(mso#n2HcqVjL5vF-t2&+ z010yVpBf$Fl0vN0aZs)SBSd&Lfx%2v8c*5o^)?Y0qgse=4rrO*H&$TDY!d1}9t|zsqiaVG&PfWSb3{+1M>+N3-ox4pHigTib8+ic0D&*0|0mX6rp&u+> z;fP?|NC0DgS{-I}#k%uJI$E=A771?pT7=jQ6q9}B zSglpC7xaM%ozGKg!R7^QCD%w28y^M&w&;q+c~BiRqr?Rr@ys2SpI9I$WBm$}S&-;7 zkwgpWWZADE-DWHxUC<8}p-aWjlXkK&$Pz8a|`Dc=(TEN`~&ZKREg zEmu}{K8PiMAV!i3L4fBT6u2-qB;s0*ylP{n4h#?S7vFZf-{q^}0<>2t!R6F#Tc!^O zRS!kt<4fO8b%cPHc8D)3DpzH_L~T9?LmpQlo3CrmUkzO2`HdgqM9DqTc!_YuN*@#< zOKMV|y3Wz{{$9`PZ#F^JEUego{T`Gl17U|T?Kf~P-5C5>`SP%nDgDeq(jJK1fJaGY zyHz*sZziNHxR08s1~EWAS`dDi+?AI@Xb&1oCznwHIcq8vHd&s}{&gcEzhP14?}Ea! z`~xf{GK-)PD1)bO*@d!aJ%zP;unov+A^mTM*MAxm8mSQv9yq$zAI9s}8+ zHYOt>yA!1@>Bb9FtSm?Xl)~vr%+_OjeE5|@1&>tbnuOA*FF6ipQTaR$5BDu`Uo2+| zH6FiP7P44Wff|X4a+Jncj`<7`pUqeH>3r)xUQ(^MgX_il#Jue38+x9|%H5i16(_w6 zJQL9tsoBeR`1{J+t?;igPS<{-xKb?Do@ZUEyd3_m0f+Um*a<3rQ zb&B~0r}6i1(w>N0iZgr-_&FZtg&+ck3d`}c=!d+6-CAAWpNH9n*UP;=4Ei4w16=u& zPx78Luq#-KYBG)1(n!Z%dEZ+&sOvJ>3mzhyAz%4o^)v;`!NLeRKFv~dtt^$>9$coS zSoYu)U$s!>@T%?of{8{_9>V0a2V^-GPpY?U@e=9#wjrvv5{b4F3@UD0G_i(t{uO8z zT!dxi6`@MUeT2)WVqCgr0|w=pIX7A2UioVRSZ`Cm09a}j3vGByqC~}hQ+c`kc$2E) zl-y7l35^soEb8-_$9fov66%^fggDY#%E&wKkb!EwJF(DaVs|$fNiTC68AFFH1BPhN z)_jq@`+!s^U&+%S-ti}+VjHIdZGYqE7F-&^6OJ#}zeM_Lo1-y@M~eUFXOyLnV!u)ot_c zztpxsF@t3SQ(7HEvxp_=PQiO%k%qJF>pb<}{i30Qwa|rA3v*Q<6dzsLPV*0vN5{xt z2_nS^9f=hO7|y@Qg(ec<#QK0|JaLaQIje1-AlK)7D~5pg6H(UNi7G^psoqXk7aB|~ z;@Jir4(|~2MNvFjXb(AM*5VVAj-jG83O)Eb1+7N$D4{>7pAULR8fuE(gm(iV#UR7h z%-D{*-;sIy6>E=jSr-{O$;DZ5>U8?LYxsvtbxKvCvTkNlYh=|3Q76%UtXP1F!=I$ONP=|4(BN` zoH?wPgM*niJ}Hpip^7r!JbMa#Q#{&VcCUeu8BfUoHM}}T2nuvKTWeGdVVe&zz3#@z zY3HE6Xnh!^+$bnl!@3C@@+bz=7R}cn``%qHko%3xZvE2Y|tGg^V zw#-(-jpR{HRLB`~sgk$*)NKPJQGkYJugo^oj%5SV8!X8M3)aQ5Ork>E2OYGgH>kT}U&d&06rfrdRovrYZ&DYHn8!npyeBq(+6hR*cSi=XG0U3} zzN>*5q3f^=!#4AEj^KJF@wb{@(fmf_p1vd`}()%Z!Xt2>#Huc)oRUVN*U>k><$Ny}?d z?Oi&o)XQ{arO=~i<rg13&$+S?;?OqRks8MrcaZT)StDu+cif@O& zs%BhFBJI~l&luo|ROEc)Xe?%Z>foY7bmCCJWEr`pM0QunP5Bn`!iMJZ)+m2`dXz!g z?@9y_3TLIr7Gt5x@zZywkMgwVHewC#&7dR# zf1y~}*qHul1rBLy#cr-3`0VQ0>q5qf2tVA;h}E*zFZMatr7WU~;$Q zue$c6b1a#3W8s_6gQzPWayTCI?m~Z^PlH*dd@Vm+o-bRgqFb51s5vX6k(T_tk;Y1C zPZUHgOii(>DPXRWN+wEvU#9*ADsK)<9jn!+d$&W{ZkVpyeB@`p>|M52N{Dh*a!>*uS@&iwTH*jci-w%suKn0cad{0MY!)xlnw@w(jJ>EdXD zLX%D4luamuy{C_iz=!e8{(?ayCiIsn>@Y+)q$T;b!A_p?!5&?2oXVM${fOXF-9k#4PZ+Z+~dF&AA53(-h<34q9 zB%DkM#C4>S$-?!T(mGU)F2u-Gg#^>5GI1_U3WT>BJTOI+>_6fIl&90wQ%0PbZjE!c zp{=Z^Y;7q5T+pzt7IkfQ)tn9P+SqUvBY_Sa6pW3@Oxp&IXtEB9q~Tp8ig9l_$SI(= z=IFPy(hcMgxa)MFtC^a zfTa0+fdq;+r8g4S$W!xlZl*xfPSlQd^e>w{j;8~}q{ZCu)xs&)>&bX;SF^u=STsIJ zY_Cit$Cu*DVS})T_8Ys@y+nup24hofpVd-Gv63xBGH|L1udoH{x;CFaGt@gu zsc>vT%`JL(oTv}#SYiZC7RAHjFHlq{Kr^Fi1lU9f%>0O6>9R7dMHwKgP5J@ONpukR z`ByLVD-iFCv3Eu4Y;WqjAhX&7>DKQ^rqacTI25^ed~63LB=|au32+UfIMFfmg*;oq&jq^|kdz+hr{S{{LL#UL%ukY`YaAQyyzS1ffzSK#5UJiFIjyuo(}FKd9F zc{zrh2KN13ZLhP~!8K4N)aA60p3=SvW1O(M$M>}0ke$PC+rWAy0GRxTdb96aj`|MG zUcTp#m$(v)`sHDU^nCMv2A~Cq3`S-7r=~M!wm4=BPt}oVRSGWAdxANIDp<-~fvY5^ zShfr6hYxFxz~H9e`%q`r+G9r)15QRHA!jKoex0&*W?!Jzi5aQF#>D^9!;(#dVk0xt z$;|#FUfR@G=)#vsq`c>S4eWj3#b_I01A6Y|wAT zR!vpO1fm&VJm5$L@VADB(~K`I0z@oKT8*X)w?0R-4RLhYIGo^!MpyD# z4)M4ShdE$an@H3zoRDp4CB`f8uLvRT)*XOqYOmWPf#^;U$@((#@PtF;Xh7KqAgHr# zI)^?^8qkIUyWRv7zZB-B#D>~tJVntRWP6y6i*=1o3i=srwfjZ(204&KnGJ1iIB*b6)di3%g@}WK>ZfQV z+KGdV?~6;tW#?*^98hriLzMZZoyLiOah5|G6adE4|LJ4Ca&>FY`kr?-YzU@v%_b@*~p-xdHbvN!#dD8J`bQcID*T630+2^J6Y zcoZ-nepfVYY~LL|1qT2=f!R3?-pWm0f(&-~lI&>Gm`|vZ&&#j9DCxK5DC4Jv>eMZI zluXaxEP}yxdA5|mO*xVv8IE%2S{NCB<5bE=EXnJ)%J_Oq^vLa@NRy)+os%?}I2M`K z8j?oA9){RFHgWl0kBQQSuypXc;SQD zWl1Xu5HB;S%!Z~2w6oQv4%F3cQv-1@?b4a2EevT~pT$Z%dMK+27>XOBK|we{3fC=4VoO~v#0A}ehs?soQN$AP6(jNtNiZPHZ zqNHd{jEr5ho0RxOD-#v}Qdiz!5F^1{QuTdwLW1Io9ZQ^kpKZzieA}+Io>x4Leh+M(v?7!GB^9gF{szU3jI$Tu0&Vmbc| z?kb;!E>mVI(b-gLQjsk80AUrEk(qk%sZSZ;pGW2sj>(jYSN~ks{Aba>_e&}^VGh(c z#$fMO4WOSsz}yE;h1{C*arj$meZ=K8i72#(bDsJD5+(Rx7IsTqV^TpSMp{#ZI&D8B z4qiB#cC0XGvvQ{FN(t*TCtwlK_phLV7!G;VX$8&8-|_WNNRD;_pjTjIeYQ5R2|@dL z*-8cozP`KD+X$}`8JzOKB(u+>Ik9r>r`Hz>F$0}!#Yx%`OwK6}$x6PoKo&vN?hjuE za5p?HwgkzRjgK?aQX`0bD21GYJX%)*7I*_ zfNcjsEM2&Z)g$z(k=Omh5v$XseYdb@Il`sxWQYKvNY*{2Wu_*BlitWp7-twAY%Uqk z?yJ7tHjZ>y-Ga2Nv%kwhV~Zpw6k8h}KpQtxKRU_&j{Z#bakhR0Lp!|p6#KpT+<2-= zgS8O2y1U&oKPaOE;$0nK-E`p+091fT+g}uYn4^Z+j)QOARrLpJU*Qe?LKq8fLM>NJizFM5eHJKz zywS~dfjV2GG1kn=m!TeR3wc$K%0!-asqA!>DEj*k%ED00Fg{3nX^Jn zoW?M_6AtZa)%YBFB=>0prO&t}?z|GbCK96W1CBzhcRe&n+LwTvsjh43OdE+pDqC>v zj&7MrLPb#?Vr+e%z}~Tfx~^4xH96|5VvX(bb?zbJgA>*?Zv2!}^*xtND0(J{lY0Ak zb$Dwf8j@J3{~ScooxHS}`1HAKJ4A<6uI?B|FM-CSP%X_Wp%bMIs$Y121>8SNiZ`P@ z?NQzGj#fg$X=&j^&$<|s&CuZ9^XI3ZQGd)!94k;#e43_P5S~OJOOz&4c*2j)+?4V^ z=9pQ+=ETvOajse?@}S4MTa-Nlv4ppl;E-zYiz}U=t0p|}m8DJ}=nl$>B7QlZlmu^n zNWK#`$u|=BaqPUDfV(k(h zRWMT*0Bh=!9m*H4j7YrEmy0N!51<$n5&;u4?!)ARWtIQ%C&3lUS@48AWcuz+-1t!? zs3ms)Ji3Y;AB0LZwxsIYOz@}gJQl+ZaUsy?f)=yHf;@FpH2$hh-ZvMO0COB%QKjYH`3ryUWUrbVP*auH-M)G#*M|cwDRu z0pb4pH-TVt%hc|l$yw*r#CpJ2WUmb(<@TxMC`==0F!?%CAfgtc0ukz3JO=!)r{bN( z54k6Yn=`Vnb&Cs&;%9&>?S~g7$ZymB6wlr9sp!F!!f@3_9bI9YBPavoS1+tl!c5R;|LbzQPT{GNmLjm#=M zfZL|p!%t?$zv?T?UB7QWuToFGY#2wtF;QgH@rs7)(F8AGGs;I$Q|o zvPqpS(&9uj>S_F6yuD+LZHu<9UAAZ0wr$(CZQHhO+qP|2&8k_p?OD2WuXXcf?Jp<$ z=H{N9|KrE#Nzcf5T6^BN;eAr$pd3qS5JNn!vP9|HCd}XwA0f(@CWk|!tOwj8>+X4r zc2s<^inH?x3GP)bAHlUN9*JFKnp~EtNamrAi z-vpdc%q&ifSveZ3)dTFxzDEfi*;}<@( z(p_vK%42JI&%KE2HShO zMozzD(DnT+y2VM}2cVsVz9+(oI5Xor$f^jRV;C*&A(UZWv}?XU>5<5p=7Rrn67Y}U z#9xzuzq&sDISF9>+uix^nFO%@ee>ZzP6Gb=%>T0p^ncU-@z*2%AEh8B1{U^zP6C!S zWRm{uu6u6k(z61DgXx0?)NB*go_~?l=unj=QmVnJBXtRTRvPobb5gi3q&}o z(8eBVBBj^m=Dz5B)v zFFW@fFv@8l2hf*uweHq-zL>qQO-xrm#p8^@VGZkQH~X{IGPdTgEP5&;tZ5Jb0ohFw*Q<$VxmZFJ^OOw8_b*8&L!z)^Vi zk}jyN$b6sT8Oxl#cbD)QzTFns%1_T-pZKEj3&i7l)swe9`(8h>lRzh$L+yug;@04~ zk}4YR;KgN+cCAo~=)p#H#TlWb-DTZ+11#$cNJ+(fh6TnAYi`@G)CuPVC^L;)#HJGV z_C1zddc;=CdX<+}O~*0=kr)yAD%D+*&z51k>3mM^f))lWNWf2s@jONJ z_t!gFr-N<)>IAkPI$?4|#L|hHPW%j*#0+k`4g8UQD=)#VvBc^R;knDC7prJFibB<4 zwOdWpR9dN&q<4f^trejW7~+>@<;S{jfq=)GL@*}A44B-hG8Ph048!27Y`LTlE+)V@ zM?TH&x$mDjKQ<>cfEn#@@M$+?(R8g#L=gCJOC#cuBX~i^xC8)$f}JiQX2UbPdpRYL z_~QLJ*69tMR_w?Rl8ud>myo(&&%bHXbVDW#2rxN~8_t*;Ka=Au2Ba&ZOb`iE=K+h= zZl)QLDsRs{u^IWH_gj^veLDreGiB9R=om#{Nr?^T5g`vFBHBvrfcz2=8rl7)yb{u- z*Au^wQ#Kbv>aFNS7osgLU%V!&ure&(xMmPh;>Pc`@ZpaN^?|U+RwMP3U%pHDhR!y4 zi4KTH2(p;V^8-1|rv)1oGEW`rmu!=WWrR@xwww^Sqd0z^yK!x7m1hH=d+Cg(!<7!| zKE^-tSx_eK>VcN*>~1yM9>shrSKl=uGnRG(V9VgrJ$HUeIn04No+9Swk5GSE8?J$! zjYc-G(^3=$`a4FhC4+;tr6FQ*EpDz7tOtlo;2}{E6tTH8vk!q(*_5e|5FE4Om2tjE z4}XRIT;Je`l9!;A^}Qn#$hCdR@_L1nm4tFd%8S%=+1L&ks&RpeEh67ntrn7z@(xwE z5H1K2|IPnEKx}BR>RNurL&YiFjkf!fMJzhnIZmc>n7){L8Ic#^Z9)Dp_y?}pAUWSJ zk9&!5TElV;7?vo40cU&T=w)wE00h?H*_QoV6YXzJ(lZX^W&)diu7!nwD^0en(TCA2 z=kqKE0?A?O_Us1`NshIx50KNv+=;v9x3Ku&oX^V_Ud8)veqDpI4gVx%6`I_`2G}=bGYXSL z+t*HAUML4P7cPEIQV_5)mKt|aeILnPZ$bU?a)zVe{x&p7Yj6K~Ub-Y|ERLg2PX)Z6 z&aK&9^QlYvl7@%pn5=lm4@>JxNKLj^f}BdGO~uF~$uqSvE-K(xjT_>&SLoLW7pvR? z)g#b&=h&uPhxMRrkjLU$UGt6)I+1kG;x0x%)B1b zNK8walbqxsT2rH7*9wJsQynA25A`3sCuwAhsL$U9j^F>-37s*6bXcbnQNY*0#mS16 zh`p3eY+EF=3l>JqUCr4|r8j5yz)S~U2)N^ZB38~Naq62-xadE!GTILfO3G&6qnREz z>3(d~{n0B0SI6m2;2^!mq{$witUCmwkoEpdU{O`sy20>CRI46d50?oWxc^(kVuBTE z5{MPq@(K^uV>ta4mLXIs>riogD*b98tgDVGbn8G84%riggtABV6^wZ^6azR5@p&2# z2Ygs3oxYx(srO)V@(Iexm5_z4TEce`a%OjcnYVCVU5@0;qn_Hs*KkvuE_Q5?VXj1D z)J%}qZ`bkX(7)bY_=9A6hua78pnJ%9aWM>Y?cC}txu2%G>f1U5bRMzjsW+puReN2B7F7<86ED0 zg)ry+0r+d zJTIG!Iur{yIsK#FQh2=LFkM7~7rS+ul^3Q;FO><%?N{Uov7mVf?-_I~tBR<+k{)Y{ zcV{5^&ms7bGlGm5zoCR_=!PYn5>JoC!yKiiEOGB`ze1|eaf~tqHP|7Ch>Rq-q*dpa zYI{A~8$+)L;BXR=Qq~>9kTo&&&iUJ9Jf!0&=pk5_NPeyv#%Gw+j=(j9Ix+JoCYIC7M@#+Zmuo%-SxY!si!j7Lhatg#izvBQi7j;oTu zCol5uhI}{t#3wn`fj!b=$u>z<9!eS}SvDL*Uz~?<3DZqfuBA&*Q8*J8`Ih*=gEb%P>nhU(c`b9h*{+zD)M4qeD^{#P zHwihl99Rd6@EZ`J^HIx)t|zeGH}GjYA%JERjd6P9Nts#s-QjsQxAc+G1(zsz8{e(= zV)fEq+$p6U=`qe-JDUT)Rh0wHdf%!!+lh(+b0b1K=5M4P;V7UK{Bk?T<_mxRqkbLnUQZLri??D!UD$w1%QxfLbl#Sdy zqM0BXZhA9iPSJw8AoZ@2W}qc`Kh|*pvCew%n@ZQ|rr{Ezme}Dgd^LF+4Fh7uNmm_e2UCFvi?PuadVKt?ZQ*uQ|on(e9Q3ehr-j$J*;bSM5R`l;Kfv+x2g(3V19CCXsH#77`xHo81XFnTew{&lgcXT zWaIuRtyS{TFm}mFoga+NM1;&>A6Pu!^9D^j;VInP_41bPgbk`xqk+WpdWP18)*8>y z`l6BJ<}TuVKXNGf&ReBlwYHvU@2OH-haEBH?bNSN#d#R27pk$RceP3mZP!Vai}AFu zQW0JD*NC|qhbHWx9Yk4i<*u{WUXxwk6s*G=Te|U*SvtU~;G%t}817D37xT{Q1f_mI z4B3#Nq%L0kjArE??!2H$Ln81T>M^3+k5iUg>pGHs`cW7!9yfF?sr3Z#Iih9HusUs9 zsV2xl_dUqLQb>JLwk!a32blVM7=2nX;_won2Jc{X3G+!(1ggU$5X0T!rx_|28o=Y8 zDv0lFb1Awa8p!=Q22<$#qmSQOB$2a>l0SVS3XRg1jA*@eX!3lf|}p0P(l|x8D*t5{6NtGkTbI$|0_ge{Z|s>f78idi1wFE{BMZ% zw-Nl`glK;s%J|QS_7CIve`Z;xYd zx_O)~461gczXAX(JrOXPvN5q)uRrYl_{^;&Jd%204#e-`kE2!?F}%yJR9X(xyQ%g( zt@F*$@kyU?H2IfYJfczy^K}w6owMt5=u0P@>>vVR*E{_IGa#sfG60HNkJ*_pudXn*Gh>icDl$SCbGmyFUZ-^m!2i z*RM~hCFx%8PaT!f@~r2A&zdu}^9!@54Oa(swsSq7Cbd4?Um`zbv`w;yur-oLIldN! z)svG%FhJ>&D#ulFhgq3A@)(tVgi2#ni{ML(S3` zMrCin_yQ7h9%7C3awMke?YbS>#jD->u2$(3;M!K;nqZ#bFIS$n#x}GvtrXx}IWpG50RA}wJNq;-}ZCLmFTkxig#4f}nE`AxuE5lydo3EFzxWcwB~ zaGZMMy+u29su?9ZR*bR2I%fJOfTYWd6DttYM{^%FCGT_R7{0}JL%`HXy9~;6&B{;0 zJaz6kio^K`l>^g2WUISF@P`aBB~DbjCnPt&B0JJ|AeZ$A*YQfg&9Rp z9Hv{T28xap#*vxNDt&aG>49!JcWb%)nO!h1e(kdq@K~HWtHz=){$^}W+;ioFIJ3`K zBQLxj@K~LHc6Rxx$*TD4n5-pQBdSkP5Gqb+vg*){j|^flmlvuHFg*jLv_$geakQ@u zRD*HW7R_bu7y5>Y7@xUopUQ;#Yv$h2&r;M>hg70go7ON{^Hd8-`r!uGrE<>QNiE(u zV^+z?YNYq^+hl+SLE-NT5!=FLHV2F^)3IbZIAWZ_H$fWB4xTvg{Cq>j;6Nvi z5|>|C3~LJPjJrW+5e1MvjPzBiV*{4XqSR6v5#;++xyy4k@vM!v+PZgOr=i?giav^r zK6rP#MylhDKltw$>qmu#Ia17Y>pPreJJ?AIzpRS@G);0z(0smLNn>Zki4P(kuQD3R zv0FlE71h@tXFlFHgc%Pmbm22k5_PAVfu%X3G~aU2C*LYWCAm+)2F;}2m#CROarkGb ze&tv&+2iMh8$&#N!IR5|dYjf0#3dNPJ`FN_`;6@#qIu75y80*^>Pz1ceGo-M4sPI- zH0biIUIYPnMr6+QdYbl@l&>wFt6y^=L*H95{1$nYg7CkkA{NbS4IoU)F1~U^=F#n$ z^%qvf80f&es*g^ex!0#b_BOU&200TR`ut(R2-zgPz24k$7?0`V&&==)9bwX&7?sIF z&H|~>|FDb4qWvO4DL~b%713x%k&G-9tN_K5riEGgr+;!=IAH3f^I;C``6I%Ym~%~t zS%L<+IYt-`WMc;4V4W%c*HfIF;DYRxDK?K(8qSMEb!1)KmE9*t6L0*`=-X3pUWNox|2 zyi?(h{Yemzfkg3G8O}iZ4AQKrxa8nLYgQe6)UjPL0R3a~!!ZWO+YNU3#a8U_*UU^7 zv6$u2c~~oW1#GpXaZ~#(Dks*bv-XlAdY`+=Reg=Ky1;-I6Gw28W zlXjs;Y2l)6d$?f*hnhsy=R?l2tKFZY$;70~io*!mWkC?^bf7*YKg1_En`Gk(hQEJG zUJ2b-8Zasv=SgIyFRN`H)V}vx6!dN<7`e5rUCwJ$%W_i-3=wL{+ zK!QZL6bm~foJ6qcAde-L#(iH&Bt3B+6(tY52t#l~AW$ecj`gUuLDQ<{aPR8M>brVe zE01bucDnrnNZbkB-vh?uIr{Zoi*^XCuW)l{*!B!q8cwgRy9?E3ejzkxyY+g0P}URq*%pkei{0*6}2n}Cew zV#rfpfxNOrLG<~GgD}OY#_slJL8Odi%9mlfqeDn+V*Z#>L@NaDY_ZFDbDx(K zO`Jfw-K)gYYxf~1R8#Y}gguGVJpwYoD;6ygv_i3?y~H3kLOy|X@Vw;GvK>xjJg}{{ z$t(l023=M0FnN`=vDM*fe*5|W69J+&+)2N{W9H;*i|lMv_YR{4Ognm0C*ic)B^x@a zNFE>K{7CA7%tfO!7`e@WG$x2M9JF7R-1X$#WHi})J0^T=G=OBL^v@GBS)2tM}mQ1;}C7&1`x$x(j$eF9tpy3nN=eQ6g;y zwhFGKyhWLJB2|Nm9q2vE5!4QazE=jXm82|d1Ke$Bk_euTwF`U8G|x?zMG{wHG?I1f z^(;oOs)QbIc~njB`S^kuLDgSI=z4f1Q+Hg{TM zWqb6w?5|5-&eTR<$V4l=;Gu~m+hu5Z6^RaAgKoLGQeu~TJX#@f`g>Swjj2phwN3$S z!N*SnQKHX)_$dw~ej*T4(t18Ng+Y4?0!B@7n|DYnO`)7Dw1)e$ub}wJ?^&sRJ`Mgn zMY~$2UwG38LU!Vp`>!2Kv3t%3W=ddIEWV6Kb{b9`#v7u`Dz^ecbEZdJ)?o9apsyY9 zdhCd_U!CVt=0^-Tv)#2t*_~|}{x1iq9h0U-5-AF@d5#xA0E&JPGuh`HdF|I5I6mKj z*J)|xDKt@$zpc;rj<5q~EwL8m^)AFw`3DC{kXNwmn>6lE7!`TDBjuQqF9~U-j$ly3 zN7|DCQZb5+s{dTc)FnaT=Ed;eSy}gQb~FQ4j6BN-(LOSffM*KVG$!hVk!xfuc{_?| zmATr#6bDZZtq@cq&?jLPG6>Ueu&(ikjB^ZS$I$KTQo{x8|^AF0c~*zhkB{5LlI z+r9m7V#B{L0sLn+{D)ioKg5RrP>25m8`5+9o5&liVP&^5j`De}$AD*sN-(sS6=fJ; z-7T?Y+Z|8@3RV3cfJzY&BaA_4V&^Ni@x9@MS8O~cfr!6v#Qx%Q-Er{qhR>r3m)2KT zyIYsq@nFW#MIl7Rmhj^sidk}qomE6PSi%yuD~djX@&~B{#W&6>ngOy$x27&gdt}4d zL5R;1bC@f7r>{+>t@<_Iuc5S`Q$Bs?t7AeuuJ7A4UoMEm9LCBikdf@sQ^I8l2VHC~~NScz8 z^S=hKb)vy}wvFDP*g`@q9ic%Dn#s*m-?wV7vjSLB%1sdqHH#Um{a;cGYPRr5Q}v?hg+$*Wo>*mW39nESQrJcf0rBA>}leW z6}u8gyyYUnzsXDTA{%5EqX-hCN^;vLc(&Nf#J;$~y6i%4ocr)xpAm-2{V=!U#ksk8 z3A@v1RWVR7X}H7{H(V+$(6A;atgxBE3KO2b@(SysAT>4jf^)Y7SIXj&4WGQe2n~WM zgDEml2$1B@-Y2IaqnhmSXG~zX&F6c=&>UOaZQo9JSjz0h!8yAV_Xutan{(HWGgX5B zz?EEE@r{a;to}tfn`|I}N`U$s76p{XO0CM30}iZ0r0uhp;0M(PClY&jZxo(74FyxL zA|KzRVf#oJ8aW7Z+M``>y3(osAX2YhsK`VRU`ozs<&?+{A`U4nIB2(=x1kpy1AlD)<&^Cb|Iv%UOU zw4zn8*?E%V1mB8y1H88u!@m8|)5w4*i|U)!t@;Gmc;K{7CV{-#EL}&}V(r(85=l9O zXYp9#oz0c0IZDq>DFgs)3sv5!4D(R?o3d;Ivm~(>aDG||s&d&o2#CcgsWnnG1iO*( z#a_mjV&r$+{@H7B8@3)>;_+ntd;gx(n(Yi*`k@}-Cf!+hmD%jn--yQ2szmAiX=IVL zdBr-3bNm1gmPiU~Tn?A1jUD(nlHt%LowB)4JMjQ4Y9g3Qu@Rk7?ez}mo zw6Z|5zq)ws0=vPd#VOGRIP+Lb(2^;AWXh44nCn%yB4K?F_QT_A)dmK--`r7}c_z_tcNlmKq`f!A@f#vLr;*3qU0q9NuT!y# zGJu(iVHFWAk@aL6gnW%Pe*0Cmqq5gl*eRe1X|!5d2kYB!LvQixgQkUc)Z>IayVVFG z)r7R~KP|7~h2#KCB84<2=2It}65ct_p=O|KZKX*nGn&x;`hhS#@ZE``CEs1Ujd|Wk zkTli=kz>y#K?+VTqM?7|Jh{lWJPci|PrbF8@U`gJ6_5cU*z!q;dw}eVUrqT~TEra^ z;}`}pH5*QQOB*UN;~-I83KY)tA<2}I69++Y-^=ynBI32YT^ z-BU~Q6X_8x4`m+7xk&n>*wkfTCGF?Vk;)l%s&%8K{c=lctQOh|B}dll-~b}@A-Xn~ zXNJ7d-Xlam!J8%eI;i++GGxu>!s7P07@&YsQLHB`FutII3((S1H$#d``I$SBi9pV@ zlcUp^&#t#^ggT5gbu{YwQ%Xn3tTqY=B`C?aavkNPMR5|wn3Bu13NZGCd$YR3E*B1y zEzS=Urf6`F;y)7Q+1Ii=Kk_x39vGQP21E!UsxXF>H&I5t8ZL9JE^BgkaiuqVKLl!v zvv88;bHT!nZ@iC~#hLeKKY@kHz-@Ktk|L8G)Vtvj$r2}_ttmm4l$vRU)w&v4(C;kP&Zi@-`jLGT*%s;VA`QjT+Fv?gj_xR7VGltm@A% z_v^t90pnlzU-zRZ%%HT`uyDsZW3&WJMqN(ZysO;mcl}6BRZ8zmkY<#v4<=JQNPJcD zhpC$I4rm4pn_Lx;ur=+09l@?Xl=Lvh9iK|OzSd-u`w#ciGjp>LU-dpgs2*0J5wf}x$%}Ei~lEXztykaLR=Oi|RufZ;+4G6nc~<@+V#u`H+& zpI0}xNa-VVY;1j7o1GgQz$W-(#rlhZrjFc?Hcq;pdR<%v#t*?Z9?0u$oR+@v0?7)h zZ@ombvV`ol5yL3P${fZtFhA_c%Mco*1MMZ-Hd;C*#`?#r2{N$Wqk_Wts!%fh;wE>x zj?VCpOjuKA2WIa(n9Jk5yAx3dOBBw-dyQgnBjiywk(od$=q53CF(`k&IIY0&VdDMg9Qs8 z#1w>U!lRdEC`GmTtr{P1N;0>-7MIE&2a&q<-GrrP=#UtLZxbHc%rQ|)lr=G2C8|+f zqe<^5@56>z(3~25#rBes4N5rRDkLKln{X^nxP)ORrR-#cr@N& z18zgVMm%j}5hE=j2=z4%7r1)_(kqwIWZ!I)!qDhcDSKzBB*#1RXJ5jYG{0_j`OW|c z&h2Gn+PBb{dn*(xk}ARSo+Jb;aSi|)TtiI7aiQmMFf8Rz-&e3B;EX^fpizZ<&fj5EtOn2xr{z{TQ3ZXUw z)yu$WYesxoI=@p6Bl&4C5H9kZGIz>=X%w+{mi1tZJpppCzwEmwnD246v{6+BxyV#X zC^x~7Q=_`1VBs3b;^p(EW1B65Em5M^cA0jU;P)IhC)iJ`Gue*mq;8(9b8k?OJ$AH< zgdIPmCKi8kaQw3YVx}b5Tuiz=ovke_Kq=TudK9Oip4o$fQ3AYwSwQ7v4MA8(>_vNpmbjAZ7N0eWvrD*Bv`bveXiYOV)vs8u#6ackeKHQwnDh(#)pS zt0peEYb~}(+l;Iu$bf#DjjX1pz?(1 zGEg8+^{ya)?)7vM@ty7%?U=r&P^mMLROl<7l#aJE?uYGAW2pi`sH{ZcgUxM!*^h!e z=S=5p=PXp5(m9di>dm_DT#B|o|7muY+&(RnA!sX`6dely)(G5wmp|L9XT7Nz{9h`O2wdFy_Uwjr+%eRH^+!yLO2>GP86} zS+Ozp^megq3dsRI9Z3}HZSb0Zzd}p%6iLxTrTcgr7E9NYzwy8g)D3lzd^TCbatnJl zbV(33NzbJbudMWJ#E1*@<%2gJ2&LRk`xO;r5K9kWTCf3_N9b4kcms9V#J^$Bv zw9U1I&;OFJ{*e;=i?IG$kNuOd*#34J|C9uOj!SLHveY`>#s-rKMRs93~c`t zB>$BAIR0I)J$-;r)sGHSTVY&f93|P@N`fY0#)e{7f{&C~Um%VGAi3&x>3jQpmJ28$ zp>UtxI5}KWR(9j#d3ziNT~zxX)YcTl)}&DzovDMPtdLTb{&gpkx<=me*ZR%6(zFdc zA%+TNy*T;1^CE~mHb$lCO`zHo9{hJMx2aaQ7PH^foFpT>$%g8^Ldy|mw6z4#XfNaWe%uC z@&)1R%O##XJ|bvzj5(h!ILLt}LVlnl0t#d%0H6M|sZG@_eLkMfnJ zd1sa9c5Q8g^^Sh(_gqwVbP%kO3(q-~R&KTd%7j*Aw@C6@bKz67#pMhVS5x+%0+5nU zk`kgKHRw%L%^a5YaThNiCyKaLo$p~dkz|u%$;%W89y_C8x8m3aR-)^Kl}~ROw?kqd zyx@8(A?!24rAjzKDXr?j_*2wMXz7BieuOg}1V!~zm-tiLQx$~cPF*Ay)D%z1n=Paz z<)NTmm2+L4y+L!|UJV*#DI87%Aw$fvk{|2Q3Wk)3Zvv=o%^eFvGF?cZ%3fX@x1u&Y zx1i6V+07<6>glrNb-4>g1YMeRh;p8gqbS9bFzfFDtmVySel;H}E1g|6VXi%j zHgt(|y?227`y7Z877vN7Hp9+t7q;f8&01xdp1wk+d-=M}hA!q#@RQNi*Qm6GIA0U2 zdf6nrUmsgs2^PQIoZc6>cJ|?)d_O|GL?+XDu zy&c7>j*j@9Cv$Rvg4(?NfUK~Z43%=IUZ5Or>C@GLXVVMR5nUnorOoCAwGeUT2wW`5 zl?D39p7G_$n*Nf=o<+Q=$OVJAe?j6rKYexQ>}c0VOz)T|B4*iuz>7iVBJx>)96Q_) z6Ba4;N{qA?U2GgV%)AVRC9m4A!$*adRPV&e4K_KOHe^~qcE4Xb>zb%*%HxyC_K7Z} z0XC)u=dbJw@!7xGsS&YXEX!ZfyawG$!@2}gLbbVL^jzQ>A-86ixNOP4B3>=Z;B1N z3INX#5k3mGv6x`8$<|!DekO^+K$&>s>Sw7Nr&F{yHRPSq}ud zDFckyxMEIDmc)`5Axc`#KIua5&gk*10a^M49FY^!FhSsB^IO2$H(ApjIUhaOhgYB) zZ{UY&UzSg~5(1iB6+*>rEFLu^s_ zdxk}{7r6(8190J4E%G<2NL-}pE|9LSwVp_F@W3oW=>eRz+cern`dB~bOR>c(df8P@ z$j*b1qlxZ|SFUGZwtwG!EV+&CgS&REZ0DpFLa7ED5Z3O|k9v~W)E_&_l4?pi@--?N z2CZnL(=GtBLdS-JB!E*Te0>FIO3l{JqpnmH4E~O~7eHz7({KKCUpxDJUtw#A&1g)Z2ViXIGUbIB_gbxl5|x>|sVRfG9^NyqRGDX( z$=2m1w-kiAj61;Lt293Ocq*)v2fK_`QWPC6|>5 zR+dN6CN~^2X3CoeBjsQHhaKZKjA`mP`m~ieDN;e20^(6?liSgzF#c+D${1!e^l60o z;yhL8dgZfyn5S)l1Re(9uG(zWXhsDZ?K1wa?GMq`rvVZ@D?QS>qI6kg=O2#iPRQ55 zOGV}jz{4yBuh!Zv&V}#lgh&aBnBX@JCazOj#MsWk`FXY>Bx3#OD4EC=**7MPyDi4z zdyE;pSmgS>7%LmX!`k@!vVkhe1`F%7^eH{V%MV)me@B~no z)8rJDX*O`%o#_B8@+!hq@2^J(3<2PfTLa#vFJkj|T$*H7f}3$zwfmeF8-E90zMIq(pa1X&&dUnraxk#{8FIgn53QoA7 z)G0nXzUT%x&9R{SW53Ccj9NSft!3waETT_c$a0fwAHq_gycv+RDSuM4Ocs;-x~X$$ zQg1>mKKf9l65F8Onjf2@$9*dee3NIz*&PQetx~t0MQx7;ZZr^FNpaXZxf=f#Yp zJ`ZUV@Q$*lgFA*zC;Y%zS?rJ;om(^4;=ft$io}cSH?6(;YVv&pN&C!~2*bMMXX*&gFYm z+bcJuaBgwfWJvpdp8}H%9;7n270sYiC@qsAKb)@87>(>DG%F^dz~{@&@!WG$JkKd9 z-ULICU|oQ?>lU6PbGH}TzWDpjm;XSH2Hg5{SSq`1k~neHgnTW4JLTvNmCM~cZSu03 zZbJY^hE};L(=850UEw4^*j`d}WHfVJ|XgK)|08kO1DEj zebhdsoJgsCc9|d>We`Dt+O>ADzhLs9=o2H~3S;UP>vg}y)nr;0-=-DzQ~n%X1|)%{ zE%?h7cB_D%et2Lh?pr`kGZEjF1;^+Z9VeWHG4*7&sR>0(s=bK9g1h9INi|>kREN*S z3tu0utkKjuEGbwLx+f>Ewz-F8iT%F76Hf~xe&!e%g9r_KMBBsfhr`%qkpsB?c@C+w zY>))x0&&|q4h9i$6#Q<>&@h*mEGOg^Y%OaX6Unr*(nnvzd{xF?3KLTOZy^-(1qRGU zb~0jQX8PI2(-V+F_r9G>F|gS4Tn?4!PGi->OQi1ocClE|nO6}|lXU(yF9Yskk~}k! zw?`0z>>trtKaPQd7giL*8r-Rgnh9D7N$SVugRL+;RO!(N3Ym{95)I-wF^yx%aNQu7 z6x-ay1GnUQGoTT3onl(qirGdYg;uo*U)yy3;RpUU_~u25dA&T_h3_kp zFqGLVW3y3Xe)6@0Yr^eVh89X#$*)|5pqJi{vo)ZlNuvmS;KV`Wy!#1Q&WcW=-10@_ zh_$>*ojq`84?<_;nwBDMduGNEFGZ;n7)D;u82N5ST-1oeGW-Dr<|Jxh@wlX!=^L`0 z;#d3`NMt{nSmeZ@vAtwOsd&g&1C(^gKwrHCHFzM8?p$~*C~DViZ&%7EQv$b0nyjc6 z#HFxv+3j{T#tbw@Fw8AldCrdp4DHh2GdR3NPmyL1(Ol9^WGhXO$y6=vD4*E2DB+E& zCBZ?JTU>A0$9+x{V$IjHb9I2islGZdTzE6l%xo_+(Luf6t}odp%*hU+ktEeB<q;ygK?%V}FN7TRC>%s~o;g-~G zyQy8Nq&O4zwv}bCc{H;P9PXS2QRL;zqdAzr?jwZf1QhpgUCS4T7*nzOWLi-uuqN#7 zq{zN-X>Nod$l6S5$tNKVd2wX98Dod`>S+UeSJ zO0Ns)-`Vwe`He)VMb;P{<>y}3e2d|6F#p`+Q;7{hrejEi33vd z!F2P~51{+0)(&VN)KHN$7E=y!8VF1Mo%7+xxFbnC)Ldz<+wEe>H^v8wvld zj{f(MFx%e+WHa^*`(ySy=ynB)ns{Ar9v|r^gVtSfI+x^t*!} zZ;@2v(cdO=85()*GRSbM;o5q_YC^{K`}cv^?6~8i@y#|IsG=0613NL_J(0`TgIW#l z?`#; zR2|2e4U|1#t^6FCZ-)0_|Ngm7{fB6pN-~c~8AU9XKai$ib+h)wVqbirdwt3;*3&ky z{uLLr#?90__pPz5TcO*!udi6C^XXCJ!^W%Pb!Xy$Y_9w*=9!Ghh*vfm3J)1ZV0#6Y9LjAliWG0`G!& zmQNaEBTutZ`-^QTZyT6eHH%#KbVNauLvl)3vrd(mGTUUJjvzxC9Bpq}RK%W3Ey}iw zr+Fq2=7%zYEu75HX9I~ULe`{x8Bpc*YX!GKZ%Wn=cmLp6?spg0{QqM*4r$&PW#l+=KBQIV}b7d=f=CLvAE00|pywc>Z)g z9?M9d4&y8u+m_M&xr$XF8owg+pcay@^kAyx2CfKzik)ke%RC1WN;KVVRP7R8u-gL2 zm7Oo-N*m}Dk-35JRZ=|&U!ejoyNE#Plm5SgDbCFC0#$01hQ~dVRM zi=Fw}W^l}>=lmmuJ2W__$-=kUBKTde0pxb^(M{eC^aaP`-p3oQ5hE-%HW$>=z98mN z9xPiB(wpFZoHbj(oQa$l$0$eUXO*OCI5FINOSc4loCKT!cwE(I?;EbBD||fZwWy(>*1!?v)`Dn;bjg?SV^e9 z<{aa8a(mVM^oxGQI6$I}{!!4a&-fzI)S>n$O&$;ROi2=g=$MEtBX^dF^WVHPkff4^ zl^(^4(Jw$$DxYKNCn!H3+7@zS436qOVwlCb3yPE*614`hGv<_TNwgbmSTH_s^AS@i z86P)eZM}3DkHE7~#?Q)6oRVU|fiqx|Y1{@8BV+`_1(vvAU2%2u^j;7;l+uV1-cRyQ zw|5Gu3*;l!d@e2h?9oN6n@C^+?Pmy=_G}kfig4X~M>z>6!4lNvvdqHc1PeVP%vJ)87lXr7reqjA#PZ7(@`G2- z2M2?Dm7XorjP{nkU;sKHJjO{2;IUqJSG0E<`ELS&T zoeX%lNw~@+{^Iu}6lrtMfEp8DD95hqP|4N;a=GYPJ=LJ$CZcfDTEX?y*O^@zqi(u; z@|7`HQe2j27!M7*`3VJ{s(Bjh+oqErQ&-?8inlOUd0Z>lN<~zt5On8KZYgAb(;#h6 zyL)7%Q9hbYzbFbJaiZ7c2$GOpQ8CJ#gkwL1avLZ>p}31=>KBHxpw>73nNruzcI&S%D!QLzzF;#Qr`GTpu zL|LjS;eR`nZ-~Uy&VwxkTj}fK%g5pbF*xf20DHjsz+;RT;`<6J!TTd2Hb7!j84al` zvrrYo(8+(<-~+C&5lT4JjJDE16Tb4@3xZ|MI2Z!IS$(ff-2tI`=Qz301?3c__@?Y^ zjo1nz4`OFUuf^iJja|fPYyKb$lOk7WfrbR`py4MW)QW0)fmkd^G8OLETfB-f-iu8z zffS+|a6}7KyYz8!qvW|@=Pq~72sf+-LM80Azy-y@C}SIYg49dg;G&IrT>K z9_nFkfBTSq%X6nAlSL>cSH4lEAwA6iCgMH(og;-ssO`vlJuKIuRgii;R=Un=UiZi2 zgq~%0UOtu&{$Yjz4m8f_wr3&X{LRr7z119M{vmtjMotOlI%{+tB{zkONM7tKMp9;T zH8SJJaGo&;<=)9*uP6sP0I9}8@td0jK)P)(uP+P4bauF9_|&uu7k#&$%sv$!PWD*auroOz@P5gT=;dK@CWyX$(*XhEQT@nq zeYIa;igv8`89+ejJ}vW6y0iii@rNQlf|pLAzqZqyRITU+Pf@npiJl*2Pc{m;qa;AV zGmL}7J1l`2Fk6lN9doBB*H3yL!UQ$BF4(v(dD?N|Y}Ja9-5O|#;&EJhWx1oQm)lQiUPsmYBUJ}%8KDV|%F zL`0z~E&hY(XDT(>_K=HYL9!UvrOG4Zo3QY1HW?4XbWu^mW7%@2qam9j=>d6j98?NB zqhCW{#_fzDXS_)Q{blk$=_VY~s|ucW*t!BLe2M4^*eG3~0KE4+BX|i>+=y^CC+n+x z_=QRzxZ8!<>J5jL!(#l8EPYFj3?D!>M2%jtGC)Sgjx~g3=6ZRFIx#lLd3E$<(UOs& z>}c>y6Hq{LOP4K4B7erng{vWdL7D_NQjeKgnCkhVn$__(iM;)0Qh4Yf#XFue`!2ahrYav(MU^kW#xW=rAXV~qtA zZwL2ijOg=c?3W)h+^WOuFWV4ZHlH2mn&sc4pWpet*uPsoj<-?Du=#-)a|?Q2^A+S1 zd2F*M*n-DrL@`To(iJ()%>;G&S(ghFNwX`D1aieKTt`;vh8}g$LpClkiqNq-luDQI z1FYe*Bu|I%MSS+wrd>B6q6mJlb1rq_6(6zt9K2zhqiN)$%oe+D=B5Z-vEEx(sF49B zdr{lqK5-8bi7um@n9&7Vs1aY~WY*;nKkYyC8xuDC7>vm<#ciJhbR;TQ#o6w&8Ez4hTPWc@JaTTdmvXhHIXWSU&E<=y`=PumtSB@9-|KjbPf;3y(B+#;L z+cvvw+qP}nwrzCTwyV1A>auNDou0ktV*e5U%!xT?Vs2Ng_|{q%-xHZn=9@W*To%j} zDUUy54P&zD-X_v_=PobW$5ZCddtk9WCjMFlGXcR8ANd(n%d9c7D-+96J7S5?JWfSq z6JrKNNxr(n^rfe9Qo>Kj+xy{+Y_!~Ai3j&XMM5V&sFz1h5bSgF0D5vvsWeZ06D28$ zn-z=NHbtX@&Vyo_xkVOY&!M~eJhgEG?fSBLDAAoAa+K)b!Lle zg#s8cr+J-sv-&%^)>jV=dcxhNif0q3n*o_V8aL!y8qTzd|MSOQS?V2lJ`te}@L3K# z9lf0n6iLlSJ6hF|#++kEf7GDGsNHtlq57F5F%**SHQ{!_n2F+5yw!7%Cy<7gTmgeD zcjCOCp10q_WC(R@HWS-kF*sgWrJSQ1x%k)?I%k>hUavc6f$B``j~6`r=d})VW-zic z+th>s+26eFjqqBd+3Lq4EwZBhupq8RB3m)1DK`|20?*^k5O`%s-2=;%*{w;U@$MMC#ROG)xb^e7r|81@PU*gVx9TBDf@453o zti%6D-1#5Q;QyLCGcvL>{!>N1NSCtPXG0jh{z7pgi9#K09RlJsUfBqVvTYPs&gY*C zN*IfU(t@(ae1GH?nr}cR;UTe!2NLx^VLb4|%fz?1xtMGYJaoOQ&&^(H1_ymKL=wIs zxTXKip%F133{XNJQZHXiJ}?F_a6pDqW`<;o> zg0h?iAW{)h6Bz0#ImjwQeNtNN;a9iK$0l=od4?32%wUstxnk-CuEy8D^5xoUxzlRX z7(n0o)Uq1_r)Y(kzOU+z_LBGbD>+QoL%gp~nu5ojI5~;8(>cI<0^>+o!JeZ`(n+!) z1~%O*RyJl=g|aJ(lD?WEgDY!>4%PdtQ>1g#hGS%RH5;1+)@GXrO2mQ?Hr0Ib(M!iD zu_jz806o{|j1hOb15_6!>Wpe93M@<=?30Ic6>p@>frmc1d=)IT6O69(j3!k6f~QD9 zO3UP%>Ee?*@54wlcDikZ%TSY~)3P(vk@X}Ioh-i-RM!EZeJs`GgW^=6&jgBA)~+)P z)zWaYbK__fL;6$bf#;~k@hWiy6zorfRCVXENCf7ke2d`LF7O3c(@vGkb~DRreZgpD zay=DPm7~`|Uo20E9uwEBy)VTIXzFA=oZb$&R>?Z;EhKPyN$c~;n#5b;sKJI$keNb~ zAkftsC#$7&rc&2EYLgBMp&Z5+?*&sBZqPD(psGqLJKgw(LK|s+?m=D58vj7*8S_mb zFBqKGBjZk_51;BLxV2;7m4pa86_=tk zyejGliPCk3qIj5I5yU|HJa0&zFQISd&B8T0-zU_^17t6Cq45#`4e^euC6o=5LX zhT4vq>`Ts#7xu>m^lf8so=@+~+MjE3|8Xq~Kkq8!g>&Fnx8BDl^^McF-N&Zx_TfHA z$O9ro25(rVR;;DgmC-Ik3ASuP3kOZz>+Fuw@J`w<4g!4(S@Z8SbF~4YoKZ6Yre{z@ z9o65=kKtydpt_I1`D=^c%#&e8r3_C$axkas^aFI>fTt$R(y4+QQ5%aGaPcB|HnWwMzIS8yd<-}hhk2=SlN0(6(#7mSA640_joC;LR zz#S4E$F0zd7DlWA{}iTTgi`KlHC(*Hb$5ZW5XaG3I>pu=BqC~yoPDZKVR0p@cUZVj zbODBsR@Gyn!f`b`yLHt#U=!!BfY%SFQUlcthI=n|Nl#F!h`6KEikVJwDhA#<_s)mD zzhYy5_KbPnph$@g$*JZ~hB!0zd(-?Ozf4$GY4cm99e$P2g#>XA>_k2JP{bZ@^6A`r zOTP5LW!<`cm^5pm)8ZOj_UHVQ$0aR;-~Q}F%qS0L=U@TA41Ol8_Oyfga0jVj84H=M zJtjkSfy`pVt8L2i;jc&GaYf~}WOGPCEv`-1mo^KssECv&eI~+SVkL?^W=wcIzZ{Ti z<^cFe+h;WNAJbB)Kb)E*?yINw6koEZ%kMO@M)1MJTGI8JK56>^&^{xh{_TAK#}S0T z=KEispnsX~e;a%Lm*)H5>FodgeE)}W>HlcH|HGH`U(a_YMh4b@neQ1|f95;d==MG3 zi#S@sKo*6CzsKsbMZ)mZYD{+yV2j9ZEUFgtDBerp#pw1oXR$G7>lNsUkQ)L)BJJI# z`%GNe-4eVKaq4@Nof*1XqXvTL)D_)X7o6aJoE?Gee;-P)<$KEAzR^YYN?5{(tKC% zq}(=}3|l*Hl%^GDR@Mp=MILy?5`AND zB0k$&0Vs@<3#PDrJEgNYRaB<4C7Y9SqC>jUFsF%aPVKH&!^W?s4Mm)M>jkfN%P?ezVp{fZeU6z>XlE-YywaQ7Ml7Y2y0(1%}WPh9fS58BN zPGYsDV4TZK4I#B8Ws4r%rEB9cq}xUgM>SRt{#LY9N2E(uF$>VqOFVWe`D!UmMq_+SZ#?Nw{mQ=N!1m2inh zUB?Q}*pCGG$U*{MyW8r-te{GJ0cjXI ztq{NS0J6)@Wa&tpkO6+Vcst5walNYi3kJPG!j|npU3dN`r7@{--Q;kNK$5W7bgBq9 z5tM7Mep<*)M~?h!{y+oXs~u_mPb*0{*dY8+B<>&`rZ#s~!#OD$aYJYGB|0^s?L1?Z z9q(`}7w&0ql^b*jH^{87KRuL`KjWEhT)s9s+EJ_`1$VStZgv2XnI<0OFoH{q@ z$D0n~ui3-mkK4CwEPI$(l2>kWtGS9Cy%RCd!RBO0?K0h!RbOS{EpgU7 zafYkZ3Qf6mZ2B93VwfJbb!7H*_T+wezVBmB02NioQaCxjV;F*2sbDRf-;^#0;21iB6iTjdQfj8CdbAtMB2AaaVjp4j$nFEUMsJ7#_GLCS1%{!Lc^pKLgADCBoBkkD zzpnEEu@QqK9&nuaxcWg(EHFWK#Bl5gTYG)NY;s@e1q7ui=;fgt&wfBy%fpz^&<~7) zx%PHM<06#TVL|9j6NW6HBB~-ZtaBJqoS=al7db>shcOu019a`N<5R4UhO2`VKIDLZ z-l<_fb$nWsK97nCSPLD|6i$6l&2;o6c4*E@XM}en%NkjwO-VbP<^j%qP?7d*F-553 zX1I+Q0z;TK7XK*tu`GctT3kzZ#y_6-X*uJFm_>uK02Z0$_m+=jFduLgr2jK}EbHjOv( zjlAr|)5!ohN#Lzm9vN4R$O77!NjbJpzQS>EZb5!3ts3L5U zUHlc8&MHPf!M5mrmp56&z?xcAn|S28(aLg1sUB`9G&aI-ul`E?N_0FJ4$!J!y$8kz zg=Omz+As-GAs1);6N|Vb@NyaA7EqP6TsVbvLN@r|{At~me0@ePv7;bj8-w*?Mc1<@ z={h0WFwoQw-V~P=moN@NSk#Fx0RfQ&`~Cyi!GLfOge%&sD;Njh84*B`1H=T$878s3 zZ;$$EO&96;N_CGG!06tBf)k+)?l>uheFbid3qv=u_XZhgp#kd*e+HW9hPf zm0E+XXN0Hd$G2dY!I)j-nr}CbYXs29o%B`0N)AvdJuFj{kZN$`7Av(5gMvh%TM8<& zHx+)KwUzKI?*ZzA)sw36(dV~nPNq$q*W-8tZQV@!M4w7>oyXbymj6rjKw_#F4p@M2wMr_$VKV6$G85B-# zD4rsRveQUuUf(CaRpqPg7pIfTj~|C*NDgt}t6TFD31Z!^#2bX$)D)XH#TLd~l=eZK z-Mcd4eV>GMo){^RqN(pwT${LhG6_XS|HT_b}7tPYiS+_Rw8aK0fV#;;uSOG2T;W|qymVmq~h4`!!nD;1?3V$Vb(6??zVJ160D{!?XJhn1SbLb1JehnQ@gn?X0H{ zG2owYWDUJLsO^~ITbEvnPc!7*C~jACb?wk=rf_Q(2lOteTj=b%RSON`=^4ZO<7!?; za=W*jUxIy~T~^#gdYv9zgkEcd12Q9!fn(j2 zOng^xrv6#pEABPSl-%}sYGfM8E1~}5&AHeft3#>jdMfT*$j^O_f&_)_)sV-=Q{dd) z{&qbNuf3xNJnrnSM2uq{T)0~_`xG3?;H1S%QJIE`SAx0ItfyMf`>66}k69}NJ#Vhv z^=9fhticbG0U&jks_fsPFpmE~UH?$1IsU?2|3qONe~ZfhpHSG}Ik^95wdVNGD|XHX z&L#v5^vWLgCiLHKV&l@BvJQ^W{v_==-Yr7e+)z;dg z*+GHUEVQ;Yo}gBAXsDgzy~&-7Pc_zZY+WM=0gOt^aGJ?}opIrK+trS$GQF|S*G^aI} zY@@ZLCd2ZzqJJ{K>X8*?U}>0iC>jlK-_~y-)FtllJLF@ussSfAw;Q!xaWB84Qg-4< zGaENDY1o;Se)yM6I|^TQr3EIeOigrz(D;-QHMMTG&^5Vs%?M zAh?`^kjPTnbroV$`!!v$K@ihaAUAK_rQMc@hSh!~Kao(ZCoZrXDp-Ui@bNpS|$}fVGm<)2pDnu5<*b4jm%5*#R$J0atKLcBD zpqW*F5Ftc*)N&cHv7ZN!b`ha~3<&ncwWtQc$uGQIv{g!V-FSde!#+7^E!|9+!^h1; zzCnp$q!eEHYWrJb%3B+FEh~QkkV2u0-!KDEsgLx}X|a2H_-jg(1huwHlq}m{+dxH1 zCc+z1R3Cbr3DF1qUfuYeDP2c4?fF~Z7?_xvmhsMf-9kS_e9!m-Tro@xCL?z=ge4Av zg-5_ij=_se;2lC>3wiMwt=1V!GgDTlHz_Z7u|bk1WwjT7*f_0Og0WdN02#x zbEB4P1VkHK`LW-|dY3zH(pRmeeJ&A(1B64(pdca_(QARt4stH+*=V?!7-R^7y(^4_c z65#6(wbRTn8#KT$cM~3ZO*-COaVrSLOFLm0hlIT_1Y3Cm({sEBHOUWEFsFYKvaW(3 z6HrBB0A-5qF?h4RSmY1~|G+8QCI96B7Cp(;pr>2hH-o@9dycHQ#SFS#KYW|Dvao{S zk%rf9KZZw*!zDlfr|zf6R;@H@y!kZ#0!mI1A2`W2fS}HsIJ>b*^2A%=yVJg{lg5gM zS7=TlMm24Qj$W7d74oz|(i_ ziCTV6_f41pf{|O|;|w)F=CX)W zQm}Q&r?-|v0xRW_cfWu4p#I5$3y7SgY=%{rX!Jepa{d;na^MNngt(F6Eu_^fTi4(` zdXx?gB_DM8PiRK)>m+?!g!FKa^cTjdjM2EPu<3dFmPfY6_f|ac%gr}>G6nr7oO}LU zxxveg#lPR-IZQ6A5@Ublo7|f>95XIVF4Du7*gbUCVp)j%#{!`(845eku#ELcuzJRI zL<-kf5uppA2QS?b?a+igMgJR)tFY-J4e|jd3q%+$?OE_xXJlTzjS)JS2b+z9#`Iv- zcQS%YhQ1d%og`I-Wexf8HgSwh%(!v6VO}5Yun$z~7PaI%x%NFw-VM~u-Y<0EKVkUg z56}L1;2Apk-+_WI9}Q+NV5Xgen>_|5KDZTbmiHA5mO1dh1J*M-?5sm8)raW>9y~!< zqo;+S=U+H(cerU@#G@doH1f`>JaH>M>*NY}3pCs-;NjuxBd6=JRPyQ`K_B4i8&65P z3YW>+@KgNtg`mmyomU)wU2$KLTbhmf++*wt<{I{#k)qtJ%5o{}T|!yuSR4L!q%Y`= zV|k?M{!!YN6Wn&$4{6OMIIEvo&HCDk^w2!>;{yBz4BA=9%s0RmUJLV*_TJ^dn)RJk z90SI3--wf3@37qLf`S{d?3&+mSrGxiCr?%Gtw-j0B$f(o|9l2J)YOYgYEGM8^}eF* zz?Rvo@v6yxR34o##o#LWjsD~SI$%0MIrnCMw*7X#?s)s|C{jgfNv+?>jRya5yXBgD zZB~+3g+MI$XJQt%eLkRXyvpe&lziSuvfX7JQ7{v$a-Om|Iq?M&26$pQZE`!unkXil z#}`1~Lmrm?8)2U-$O<1|UmN8UMD>HMdd229qq+ek9EiM5vf=ptt*rW5jh$JCEXZTj zpFb?{EfmVDKy(#^$Ch=O2?FbheiOL)aY+BDn>pYVq5jN-e_{{1%maM{Z?r{K784x8 z$(SuGv9-S+|M#4A5MGHnsQ}K&z%OeRxphkg^esxwRFWF>X8KKW^FZY#-%{YV=JjfV z#T^A4cI@AiLBT>$7lgL>d5Z>x857Tl=z8h2L?@lV%zK^fXiGU><{S8^j`Bc&ylD5R z+sTHSOw(*1basLfC&q(1Dh*wK9JNieB(jRgNQW`Am7SqnnR!6@GpnFe_UIf6!H@EO zc&@-c&}$$-aPZRY(7hy~quQ%IghpK9G@2e$WD%8ohLC0jMbnWGjy9Bqa{Dg)Qx3%m zw-_Y#cV3Tyu@*kHk-{^POI;#PvZR6J*)=qbouFzc37zLmmOtjCU;40HE|}y2vS8bt zTB{-yyOP*rAg;|N)8*&q1~0FI(#8!1jyp7Et2)flC((htHu$vwRI2S}jRH6PbvjKy zcL5m|@7+|CdgAu}*x~#1Y=lD8iHZh?6@%gYlbkdGm42;KdU)v2y(Xt*0hCMKL|C<1 z7E1RZWYt!vTVAbDvFFF?IyC7 zm&Q=)HWzg}F(*LW#Yu_vf-);IT@i7@*I!fqx<)9nKQ4llB6CXGTduY3SNaAq1~4qz z=2PIH$^lomeFRR=WBvhXipJEn`z`3wa$b=7YChRU`74MGvcDHEn?iJdl$@|&)m39) z))BgVYC#fph)la&=(h1Wg7(5z9lL?_{XqMw*Qu})(IKQ{82F)5Q@*gPx@cGFONBz> zEjaplYJ;zCEWUDfSX|0m?u%8VjMA6lUcwQyk4A8=pb4%?5;*2Nn)kt6Z#3sb*GM$! zZZs*@5#+K79~wJ~UBWqF8_EX*SR_+>wJqbdl<{zq9V^oI;jR=>{q#&hl^_CL}ly${RxFO_UGiOhG&;Secp4NlfxQU|d~ z!#Bm*4*IwI(b9-({3~UX=nfmbb-v6m6&`OzKkL+Ym7=eUteiKWZMrN9*Axf33TM0$ zi5i`U>sP*UIC57E&|zs1=sG=b%REwUoU)-PTl%8USGdm zBV#jl?o*e^c_$SWl3N(o+Av@J**f=4KIN0nJ{z8Yvw!c zcs^yDJ*^1&sr8C5Y?qyTXz-_@B(pP3L>sM9iHb{9WZe+IXg01d9pUx*B`oVtb2rjH z=^8{5Pc!L2jLu!QA|xj%Mz(c*mRd1p$$EbBmU{^$wZ~rPc)wzapy5Yk@>FF$r3@Dy zeAwZjCAoRu$Zibc-v}%$$yJ$FoZWQ7r9}Y9JW{#)c8;dP0S_MdoYx;?xcGLAvuqxK z1teN%nm*RS<{@gl20SNU+gI6`ovyDRL0U3bO-5Qu4A$@j)6X)A7? zzLj~0%sWvWd)d$sc7S!p9*c2??}8W~=Hq_hSP*XzVGwUiaF_kd3Zhc4sGnL` zv)KB9k}Eo4C#jJslK!ISHevX2b4l9#m;IGQx);RUrKb z7jW36`wT5(kTJ0}o4IMNX$M;#9?y+kRf+Sex}0N}+=^sbavz`tm|4BNyL^=tA;Xfy z5l2x&#uZBS)QJ4DcJ5aZ`b?D{{Wmx*gNQ>0&10~T{1fBT37U)G^P`EaNiMvJ5(s*W48fI&%v;mF z;7mI7KmomX=q-gqBA24BsjvLWr0REqvxN4 zFNx=9Dxg-i76XS462x1(Ct)oH7s%QSw(4|hv_KC>XXwxj@+&FBGs#Tr9VV+Tf<1#g zmNc>rf#|!ecB0?Pv-{~_o=_;x7x_L#wvnpxNMvA~*(ET;blgBPhRC$O6{HgNl0&-@ zJSl6b^lD5Nwhj`RVoq`R(bRD_#J?>5r10qY5Et7gzmAMlOi=1R4RIO-FH^aay6zXO(QRw{6|m3DUKSb>Lq zWU6OjHe#5tq1fb?z=>~QKQ^is))2T*z;(*xz;P?U*T*RqY7J=J#fxOjcC0eyNCeN7L^At^Ql$yDljp>aa6;(aW`f*GF$Nur-)VAa#&DDrVWg& zDjiYCswwDiewcg_?Vc-eDvsH1cdiUz*AqkCc>&^xaodm!A>BZA7k z0j`ri%0EYRT~)+AGG!a;Z#-D+(F*Tuw=tEsDp9~mzxw1TYzxGeQl8R%J0gRr&?4r< zz#kmLc(Gsz&FYR!{^0-JmgdgD;$IpUDvqih4Bb87@QpW54u-^X$w8I080G^bK(zM@TFeEp@4`k;C`%&3+tf z!Vo{7yz8^)C2f8#$K%=kgVg*~SYH+vLjqD*wjZdQx4S)B zOV*|sb6XKfK#9aed~8hNy#t~Si@;0R=+wIXnV^y%B+#liKrT-xrKAU{bMMYu>3d$oUU;+C%qV;#4Gt>IlTSHkZo}G}pPbzw5 z9LW6GizrWQ&BZBYM2A_tz<80(5XZ~c;pD7WKn_R2uPS2h#J)8Ys$6m-h#yRF0qK+= zhJD8$BnV}2Wsg7fCSbLEp~WdJD2SO&!$jM1j~54y4So_Csu?WYB0QoT_$J0*_6R_h zmhh&X+$z;+c+kZI&Y8TuX1FyUuv)vW`fQ%e0ydg`;e+rgZlVI(ViJ1wLpnde-ljq( zU>c$WA|aDSy^5nAzDfmV;vuJxDv(8U{00-he7@slNaY#xO}#0h$j9IaT|HG9Qch|S z#8@Tt*eTR)7@g~O+$YV{n(HE&rnQ0-dFsa444u~s^I5cez9V8$n)(d_D!)Y_dteVy z9ZyBs3!Bhg26>ps;>@oCH1Ei7f;;-b76UEKtW}8u+CEXrYi0OO$KCbC8!BeQ+VLo= zy?LK-$C3-Umk4y)hOL)x;A=bKTzza5;keu27v;Ej@3ec({xF6tiMXB?tt<1bQrn)o zP|=#dcw+Jb>bhcE@e&j_K?IaF;U&53MQ6U#6&nwB9%dSL6@wq&f$l!Xg>j{TpRoVy zLr~*d?T+Cgj#IHsT#`UErDCWgcpLM^U`3lpuY`<8`n9q$wzP6@KKYl5F42ZmNuWd08i%zur{nVJ6;nP+R*{7D8y{JPSs#~&XsZks$z zq_M|O9O2Y3e-H`{`}2>VlEM#7IU5jK01KYVlG#ysh9m*l^B52aS|lt61ik zGsFoM%T0Dl?U;*)QQ9^?ux2k?_~MQ!8x+-)URrr*+xc@{CC;i&wE?6lQAgxo9Z5bp!XS#VsIPxAG%^+Wv4S{`nOQg0Gewh0sst z^KVn;8rgZ(yQ1F3UE3fbwGEB46zz|aYH zv3{swJ~U-$?&-j_%!TuD@X&Dd?TG-Ox!g1g1*hu+50KoTvjBC(IBq^8inZ;4!YefR zm-mF}IY?q|Zf^R$K49~#v(VzOLhog$AYHe#==amaMgu&Z*~C$=?v&`%2t?zsiJ0_d zUS7>s9Zotf#P6{2Unk8GWW!ntI^$h62Hcs>rGQjB>E)@6T0~{7(KHpS8&DKUU(m^ z6!Y0LKG%)oZ z`bexW1dO$vFJp1;SMBjL6<;oQypjP=UDO}cA0&toufLD1?e+2*TYejlh<_o8Tmj+Q z>$VaF?K;%cB_=M6m3Vwu;`AcCSZXvg5VLbG6dwosn%jDK-3!x0xQuFu*^4lLomkrS zJ&D4cd7pS1!|>g7!@ANI#4du28RGa?Jce&Wo=`-c|8Jtn(j*M(s?rh=HF*Yp*csWI zQFRoq0(39VJ3}{mEKjulSdC?k?oZQ^8xeylOgn$7$%L#2;`S5ArH8Q+$Qzy1GNR!Uu+uCv z{~Bfe70W_K&WQ*Ptr_WHE8LWbGgSB7gt2fF4cr+H=`J~ai=quOy%Sfc)c2T|7Xma` z3*t}*Iob!gZ>b`-4`^PpB1EUr#Pbf7}O8V9Pmcv=eqXrgp>gHWBRmyFb|h@Q0Mao}BlTqWJ1n320f6OPadUSvs92;2?0&UVJe>>%I1$Nue{?Jh|MoU z#0WIAFyY+(TfTzYfp(ioV)7~oB`8FnLGc$sN%H;?^T6i^KV&W-7m1NoWwc=LsyoNB zhZ?3SAU(~5ntTDYzd))xV>~JAU6n^LG;WM5oCdyDVJ7+>unUi+xvu;OLl~u#Rxy-x z_mazD>nWF<6jWfrMe$0tMo2=d^F33s8IbB0OcBf{Cd{m5;xy?;8i{gj1YyZ#G%o8V zy-216_#}1Ia802~hf&*b8`u=xFoh9-%m6wFvf`{KLRX*iFDiI7rS}IX@hsE7Z~BCq zEke^?6ZulP-jyoYJ6q6b7@!>OSV{|!+yG7QQsJ9ws|;GYaqnYOy6yo9{TIgM7W{eU zft>is_%{))AbvJk7P zF;AP4!^u(9%Fy*Os-Qk-fTI^YIEr%w=M0N7X&c?h6lmj%D0QV7AZ@98nv*Lit_tVp zl?6<1d4`RW1~St7Q&R@CNyqLoOjV$WY7kr=tAV0@g*%k(Aw5q#_b3A*DFhd!6b^y| zgd;9ERGlw~5$DtpY)9HQ-^tRcq6c4z#qq7EWbPWBv<}nYs63#mMN^n?Ct^zTYl1`O zUb){%$=$Y}6UF#5m!Xp>S`|8yo;CG7AEB%fnF{I0=2v`(`u5o!&BYV{;nhiOG1OMte$=##g*^rIRWw{GH*7%o_Jksin=^a0#rv zPQX>{sIELNPGLPjErD)tDclAX=*)kj0ka%B@^uK2a2YaYMp;Z{V@z0JZf17MWm;K# z>)m&9m+rJ)9O>b;d44{Ink43V4GdBfn#%rE+!ooqNrb(n5?84bT4|!WX-vykMZ$yh zOFyNAk)0MnfK7=ThtLxHkz;MzhLOt}Z_GzY)b{=SWw^j8bFbfAVT@g|Uh>_%DK9|p z(@ZQz7!OEGK-$}ceA1!nmK|$L3G9v8X*wigcePY%@i|s%hO^`C5q=~Qo}_ZuaO?}z zimE!bR=d=+rOM?ov`>sCT5K&CyVWzuj>mn=xbb`vn+UG{P@4#a$(r8>d@pkrPaGjH zwT|cC_%Y$BBA5N_y6A9a%mJSmt4`}`Wt;|^lBAs17r=d`unP{cR!mgNG&`6OXsioe%4y3xYK(GSSbf{^YHipu3=Mvw-{3A%XG+^-=9V%|o3IWC4nNWvxAQ zYZ-{+4nGyx;ZnZ5gvseYrAYGnJqXM3etm9x;clK}%xAuI)y4kG@HT{Cx>G2L+5Dkl zY7uRS)d?{PXr;O_duax@YG?mP3{U(N@goF)-_-gt0BxFDOixN znjqYn;b%KTJszF4pH&%q%KqIg0Edb_R9>htXohVaWUS@N^AKW^rX4fpe@3jEH0OMe(FaMTR{=?$` z7pwfstM*S;$@#Y_?th0>a{e8y`rqn3f8FyxaM=C-ch&v%iU04eI(9aOf1Yz#)YPio z7(w*q>oxqtDvKqq?o9LHIUSJ7`046U+xR!Z@hn`1)QMCQxb9ACucz2MQAjy${efUJ zLBvR&*`8lb+30({(ke%HuY4Vz9qTESE78t7xoV(OW_#TkQeu+?Q$#SWiqJYc)ybP9 zT~x>O2KRNcNh}J`q;D)&2pnD2_AOU{YtpzIS7x?`^%pq=%gg!kxeO(K>M5OC+3ywP255}0)w>(_CxyawtkZ{0W~&$5>dzLvVH_&GRo)pU%36gs zYL)RtI||cS6U3VIm*BX<1w;>ISt1GjAt8#yBrpaNhCYZ) z6;tBee`#0i)< zi&r!`%h9r~4=UgchP?ZWwh|4b=>h&>j3k{lF0OoVfK;XIFQvJB2F z7uF0HIP}ihonoF;Mxq!!KBe`LP#BhCJJth=g;veV{F3lP5t{n&5e7rEz?vNi1}xpW z`Yml}2}X?~G>J#ANiBgGZ&hYNho+Xx#l+9}?BHg>%B_|wU~XWZcye{erNrpG9D!V# z(}nojdo*aYX{AP<4(7!Ozi~D}1H!7){Zu`M&j4$y$BhI$i#&s-D$di>gUO2f!=l+b z_=Ut4PS%}#IMps*c(A1#5Vqm^ZA2|8&Q8LFQpYy&dbnJbPSwluaP_(NSZEzoJqQz{ z?J9$na5m>U6(e}Kwx~T+r_zkn`KHF_6a5}Pcne0bi76Vk6RGj$sfLyP; zaHf+1ZCxT8^LxbD7Rcex9rmdLC}@xjY2Jxy#_HYV^pEf{QP&wPbU7jwWs9GbjsC)f zwDe`lcUJLz_q-uAPD%TuP}FZ(@sBFD{QF+FGGkP)r32V8W|)+P9jk>yl`HweJyFSL z>gS5TOb$f;EcOg7c|kIW5EG`-d`45#8uvJXVDSYJTMGbG%V@4hW@L_%yj^7DuD3s) zPj6x83rdR-OR9?kd?Ub-UR*pEGqYzllwC)#9)IxkG~Z{Z4-^pHwZRquj6=q&OZn!3 zaYOan*Q&qLgbUHZN>8N~6;1MQ*Yah#971pf?9CDy|Ea>mxPb6UhC6{*|tn={1}3+0stB0~2tiF$A{jk>2sL6$#fyT#G2e z9tL3VfjbTP(>Yumson&xSPkQw4F8iK7JYdIB_qASm;6?qV!dPdLCEhp(PK#nL!}P> ztL;bzdY;H1=_wv?t$zTT`gS04q1U}c^OXfp;wV)Q&aew~)I9MM#LXR=JMO(T_6`~p z9oL&wx)*j08hr{HQQE?f#A-kPxAR~Ps+oYK6<78xkK%`ve{A03EI`NQQ#5h&@t-hs zgRlXdk)7}`)zmt})z7pnu!3C7gKMcTT`u|*)IkrkjD0liI*%G2q*1bIDr5Mt%DzIK zZVn+K)c{X=L9ZYN!0nWWX?JieJPkn1lEQBD;Akdw%5>vtbKNA!OM93U?4m8+FtUuh zz@jTMvE9YYM7bgTA|u1GH?42}9jV+gE$2EwdXw4CxK9ON+z3<&W&>$a6vR5;{x9NR zP_v>-)34V<-{lh?Ko^raklPk?l#9R@?*c#_nKWR(?z zelW~31cuJ@hl4a7Axvq_TZ`&w4+eY`CAz?7jfn;1p_TU`zHvU3HB#SHnHp{zXxL#f`*f5IlCZFBqbL) z!Z{tJDc%3z*SEBv*de&Z0iuJJKZY$kn^CxF-<-Cr$=0di9I@GXngSh+TjlIow~JHs zYy%o>R5cdyRq6l05|_}CkkIMCg#e8Mf|l$9dQxB%OU39TE==PbRYPvuJ(_}q>)IPK zl^`0$SrKiLp;TbN58P87;`C}k-CtyPqi-vS5Fc%qcbK| zxI5K)3rqYUPq~V3gxo6u$j{eKN;)FJ-|Iu^cuGFT<5Ou|j&{;`Feye(QL>JfGK}L^ z=%539h$?2vC5jtlGE>qE5s}%`5(oWYO)K!&0TRe@^8ctO%!wyyYx1@kj~#noZGpS= z1rf9|Q5elvvSRDW11!Qq>1nbzYnSz#j3^_5=&NI0$mY{?!t4@tnZs!fRPEK+EP*6V zlEj>Mkhw4p6*5v?0tsB||NZk?+K`Uyq@#wOeDN@i{6r8H70l_*U$ErkMC^`fe~D=i z?VYjp@UilJ*u^ONs|sm_)LDn|PawAaYbFw>BF8R@EOMf(7sxuLgC)NW$pk6!PXQ4q zb%}-(U05S#Jn*<;03xl{C1T;XZxbvodWGbzOt2_M1r*A8<|Xu;5w~7F$#&Nu_wT8Y z-w`*)In+rM@x@0t)wbO3^_t?1GgMs27Cw|YTxjs3s)`ac*h7C*So;My4T(1w;C0fE zx#?p5`(MPpQcgD-ukuIb?a{`blHDU~if)@c@f4hYij@u%kFFzX^0%Sft!G6q7L&$M zNycUo=i*dOunCi`IVNGM6(&+>OL@lN1vFxBn7l}cgJH@_R#@y)nUx$a30xeOv+N2J zk&00ynA7n8(72q(#B@}n3ewVj^A?d0iP>>_VLa$FM$kLaCL{%$1($dc5P*fy`X znA1M^iJ7L<=N?Z#R!8n(3ZumTWiHICo=hqEln8b?=K~$Zzg(>Yti=E(a^R8na6}X$ zlZwpdX&ucF2fhO#+P1^}bn*hco(*?2k*ZAj5Tl!nJ{}{M4 zLNRhbt+*Q6tQ5I?3O;*`_*5&>07^Y{5V$a6$Vk~Oe%e*5k0U&FPYpqaV#fRg?qD|a zKCsheEqNV8i6o}8RCD9i0)Swa7!)rNV-4u6rRgP;x3dY_MtFLfvS7^O5X=}b1>hEw zQh3=dOe<1!@t4i;y;s2FoQl9(XK3v=c<42aF1An0i!sny#W`Zt_)#}hzb@g0Ma}83 zVxE1h$m1xx(!AqNRs{w8Os@Za4b$A>40}yZuMk!O9f{k$f;f*P_(-I&Jg!DFNE>H^ zB?JqCh55JqoPDAQg&YaPfCa-RXL1yPMBnN)yv6W`gr)>}?_(cS7e4q3iNQ3BR-gb* z6bn^u_9YxF+PRjI>oRyb zP3uGG87xJ^@j~#mYt5C5{D$mzT-Q$CRtbm2rILbN+bQkN1bLF@icKE8k_J>vBJ2Wf z;WYu#wfB;5CR@58;U%Au*B$5fX^uiZ@OqZJA1?KCJOe+sZTRna6tu&{$96a}K;w8H z#HIPO>iOB{ND@<~ss|MdE&i3wMS&hRM8;17dRuOCH#a8rZK;+y0ESLQcomPV? z>V;m!?S?e6n;P8EmTUJUa9etl?B8OT7s`I|Gt-+Vy*6WeIC*^`_W2BFX`j1A zRmyuMzd=$#fRm-A#07On?+%ci$67{#g_HCJ zBOKt^jBEQEFRW`#*~3{)2n}g8#p)o&N&=|MX}6 zAAHi%`nf-6}(*H(MrvKLf*m?EwgtZ~`jcL_;6tM^-Kbwx^MKKk2 zE-^Gd3BpF&ijXRq!Nn{rCql=ZQr6_o;%%r)v}tZUW#mE4>!s*8*gZAXSs$SjL+@d zzhm8!s@gyr?*?L@ua$` zh!CtAx~gfzrjbvfKZr3-f{Zq(B!s^}DWk`k*P{G!v-{@#QrUd{vuqif-S%<~)JJ4^ z^?Tn;kg{qF*26`bEYs8=!OL;0+?;l^SnTz{Aso@W=#|0H7|W=y-t7uzQXjyi7>gsP zRkMwwHpk5POXDuud;0I0Gh20IubkO8#k75J+g9fb=}cx4t(XNS=Jq+h&0W@ieVS!I z%ZX@5@oK)pt2BEtpw;-5o~23!UaMVgSJca&JzhpWFO^-s-w)3U;1aqXxL=h-$KK*PZQxe6lCHsV_dXjeHP zK!Wd+Qz2;`pQ<(%T~Zk0D9^=Ux2(-vAyBDWp;4;-Jo71&Sl!Nsc_MiHOyupA!E3D0 zGwM8^9SWl*kmQNV`SuC!HA%A@Fm#bO2P1K0v9>!XjObzFD=V*miWLC1fZ;F=+k&R!Bd>g6sI>^sZ5^}hJTo{k8*T5IoUXk^ z7Yx%;FokWI`8my5i&KF8`39pe$AT5!Q=01!E+12s&|t^Mo@=0^{O)$xSO80hw*`s#ULgG(cXtVHC1^w+ojt?`G7gBZvh5+=g&0VK%+J z)m`lwzVW`=IM?;eaXSGV0sy+?OQFhm;NnZ9k;4J8b??A=I_l2-peeqF5*s{ZIO_IO zuK^`$5z>&Z*Nm9k1MONRcL5zqL<`0a_$MaMs(<$=kDp8bWi#icXUuM=5Ro*Ymoc z*DiBoz*g{NT;i|ZxYSTVWh7+d%+zU;0$2XuwM09&G{55z?sKr$>Ao(=$!wdSb)P|U zza-`M732qH@h*;U?q*k_MaVFVJ}-*((GdB1tho43CwUxA;9xb>H@Ix#53Xe7x98|W zoFfZWP1jwGMn*yn2s3;5wQ^@Z_9x-=aHKVw3dvYgkdAFbh)Fd=Mq7JbT}Tg%g3zdH z{HUqZ%QT5^5&e!lhHY{i{mM^MmOZ?KI3s*D+EchZE85#4x}brRvoYZ41>IHf#1U(j zqZ#h!V(XHnhdF`PK-Wk_sIv5sgy9_pD^8V$1_dvqFJbAwE|Uet>4|Fb3l1hNnPa-# z%wLB58s2`b*XvL~hAm&FhB4QVd25i=v6pKqjL((V(%FmN9A#GkkPh{(c~4E7DX5tC z(+MRlHu9p31+$qh8Aq3)Shs7Kw-{$i?fc6BBR74{bJS63<7nPA_RWS57SvUolmOP@ zoH!4E*Wl;bC825F$36%h@L3u)9neuXVG(t%3WFv9LGKAKcXFnl%C*sQunc3T1RMn(!aZcNsK;CebFG#)2?2 zq$7t2;m{6^Y-czrZIPf&=IP_0(usutJU&vLMHV*Ld$}H3o)}I8`R+Yl1W)jUcebZv zr6ca)F7k7Cm1sXap$kvHyY zSzAG~@nZs90-V{8V1#-PL@ZR~Qi_#cj|IwG!)Clsr)dkj56h!$hsM1i-lf)OGBp$(-!b?fpkC{B5$h3w-6c&9zg6(7R%LHs!$~qs za-4>QAS?d#wF|CHu>`((Eq@jv&t?J&7AW$*xp)`$l?k-V8)#YBMK#zi-k3`9){!y6 zkYGe)A}F~q``((S{+63lpyMzhH(h>LCo|1DE)q6&Cl1x|x*TGk{*wV`LDLf7NaDy8 zE^Xo)(cA?x+J+&U7q{xV!*~+<@MBzUPdksW#@hJ#ZjV60oaTp{!d>Cdwj>dWhI?%i z{6B>Z@L<*-l*!W=mTiNHC>tYu136n}FVRr1&z&oymCBpNy$p}Bi=amVoq2Fm2nsfr z7=clQ9E;#RBj9g`5^V?=!n(h4_nj^Q>qqn=GEX8vKT=A|xq#LfR1UyDsS6I$q$1{% znLsKNa%l_px}Hcg7rVSZ`E#8~nYyLCyk=99QNM!E#7eCgy!Doak5a#4_eSQikQ$DJf4unXOY_UabLDznx*BO($sh? z1ivzo7&tg}$Sm#I8xa$c^bp+HZG3i~I)T#dj-;lxVVu+NWlu9&8ZE>XEVB|oiNYef zr%Ds6CefekZh-@?psvU{>2*$bU|h_ZEWKwcR=19tuWn7MC~yS?YB20doY)_1m?JBK z?ry;=@m?8}!-`)@yqNKop9ZV{A~WY5Hh!GQ=atcR)3qPceU%9&oq$qR5zV(->sn)s zd=WA7ZpkeY3ouh+mS=LyrmKpJy-Zos51NTlr`(sQl4KN_Ho!t5@3AA=5hI6nS~dK( zk1^KBDJu>{j{B$O7kjg5Ax(iJ3i>Om%^ZVVxi~dITm%UWTyW&O+DBlwFp}|;B>Xq^ zq;X#1t6i-bDV?tvsPWPZP2QpRc7rD9lI2F?dD3;1QQ6}-Zs!k{VujPsrEewOLrQtg zfX3z&MwH*?d9a0?c^^4Hdv`d3)t;lN)_8ZuzUvxY@ic&T$L z5l*oe@q4m?Uq)c!M}ErfAB6rca=BfVVquJwUYBS2q8aqyAPe_7_L}MNR+0QU7$){vYC~ zf98q&_Z;;%xA6ZZj{2J!_`l{TMrKCVzl*3H|0tRpLH1r!{nJuX+3zT1ZErPVN&Inl zma$sN{Rx_ZUSj3#X=%jC1>(TN`v-Pw` zCl32E6P2ZQ<=Rg6CnYdhkdxH6^3x-UBZE>ED?XWwN!fbfH2o1LA#qmt1pH&qdZ~!O z)(5>&VYjXO%=fa`)BaB9y~8$kP3GPERODu_*0!C5rI8UL6fJxl=6#mGX56j4Ve&Kr z{!SG`#XKp=>Zd}4^mV%6nUE?9QN4u6L&0v!W?52A`3ND5z|WTcFQj}iXUc>H-d}nR zOl@dQW2aiGy%JY+tcp4BjhQg9VmFOAB|f}yYn5J!$5P`y%jd(|Oml{_gP}yKP{Jp0 zp?!-`D&_S8SeV)xq02L<9A}}0rA*|iaq5ycHi)(d3DQ!t9DwaM-E?j81cBZ7mdoOS zQD=j^o@Ii=!k)FxEwBq_86tLqJZCz6|IzP2Z>9qW#l4nExR=}FXK29N9JO_8+qH?4 z_MG*2oAza+4dwZZMeOdkbF%vqLUp(CG)#ut(ci#8?~bJ{JA!jiqOaxN)hurdp3QmJ zx%q|S*~jDja967__^F`A25j-0pK8$LSN39rcxL7#WI*UDt~(@=3R_Qr-PO9mZD3X! z0~oh0hf9b)jeTa-0enl}4Lg##A-Pf{bAx3u;c-to3TLqQrGF~W{HW8B;H_*PZX&pR zK0oAxF?U~nv;${U-clbe1a{?}As{3fm0(w(cZ4DPE=$-nc;b>tF_aWV zX%AzQq+F=!)S|60b@FX31K|gAo%vufWY@`aC|RBtXjIaD1y2~W`?wFV!RfTuIPX9`U07%3fbfOuesb`B0Q_&p}j5kXS?2hbJT4gx&|wBU4ZF5Nk_ z_t4Kz3RF~Fd_sm@2+Sxd#l9a()CG1V9VQgFa3FSmwNYbe@&P>d=w>VnC-!JWUAN$& z{_GC>Pb~hSh!^GrF6S>gjz6rpq6LJuS8I^A?a1J7RFsG%wE2dTKd%U>>G&SMz*7-` zEEkysw8uW4pLOGs>d9_jU!9E>zMna2zWC`DbR;}=JwoTXZG@w9m+l)1KzsMxguwC= zKBf#9#u30n-`t)zTfhEkQ$Ae64e<(XVS1wM-xUZ7;=#cypDttJh1 z_eBC5@L7KKkZ~K#NkKl-4AzT&J)|(aQPL*DfIN}l-RX<{MWix(Yo@OMqVM}dj@{RF z3r?^Z-V@VhT+$HJWlk7*nU)njmrc5+h*bnrt0zpHpR`RxG2B#0@}}0bGhs)*mtBZ` z6{4?p+~yRHJ6OK!SyearW@7wigN1rKfP=US1g5OG=Ugp@y%tB)W7LMqBxMxV_9{J2 z3{5;NxSOk^x$o&Wi{;(6|J2pJJ*cYXbli8+(lg$Wyut1Wv{bp*R&pmTkFWtmB_v5Y z*pS;IPRP#k6xJ&#L5?+=SM}Dc)En22nX6ad&`>k*BRh5*4xT{yvs9H@Up(E8i$lm? zPMAxXV!04u7y1MdmAzLf;cJAoyxT^Cg#2%*KdR+1Jf0tK-=W!& z37hx;qZx5Pv-~oif{3716Yd*`gs{+@^w;)Cp7S_~=IWaiP9`&ak~Bl*ThM zd1&%Rn62c)g_cWavOP}He`RNS?vLsxBf{QjVq017A)}?(Z@aXu1XK=hHlI&!zaY;} zo9`Jdtyq<|M8`1uN0^#P+yzH3#CLbdpjJmk9QZH$kPU0TL~|DN)M=3Azwqo;-4|#u=JR{hyb5)pf_K2g-q}}j!@Iy zVh;xf8D?i5{?7eex>1iJ78Nbx)}F5oHQ9naGL0Nb0I87+bRk0Hbr8?@`!Tui5))_; z{?9(y`Z@FK@FEJ4D5awW@k;T)L80}T-xG5IwW$ey9(L`@QGcK)6>>#r%FaO zLxzG2IkZpX$j;S-X?59!gZxmk6Cc#UDLphEx=zrKuROK)`WGiu_jYNyuNHjiK ziGXR3p?ek`*z)VQ8otZPK;|@OYT%E7L;C9=9kXcumU>4I_xU_f)knQG{y5N5Z3o*5 z?y0=ueBD+W13;_(aFJDDOb)M}VV=eVM7L+JcyHG&K>If5`Qw^%#a%u@0Vi1|JDfE; z2VO(Ex%UrUwM&}$@H&hd&LvlwdRKCf(=%TcF3giR0KZvW!Z0IN4;r%qOSUy(&Mh8| zL$FR-^IIV?olaMn^4ypQt5WHofR-au5DL*OqC2s{T41D?ECI^` zXhr#J>$x$xcU2X05rZ$nYS0-eEC*9dxChQ!$UAQHjg`+imRMimU$G#{Ttx{ol5+%=G_1I-~!;()QT@8KC^%Z)5*vPZYGZ zvUO0j(>FBc;sOXdGO!S`F#aW2@bCcszie?C82=3TXI$Wa6~*^wCOHRNLq%gJO@N$` z2tdi$%?TiG{U-rX@Sh*z+5k0K0}EqAr$5&qZq2|%$V~s&lstc4|Ctf^&&TvX`w5wt z{v{WGUVSZLy$RVn=T{H$Nf$Dc+V->}_2dJKuG~<8$tzP{VZiP{v9c4o>F*+q%XH_GkanBj zfV~0Xk9@2*+R4&_Nu)2XFP~(!ER{wVDoSaK^3~E8$Xd)cEj(7Q4T_Yo5)s=x z%a!00$2WyIntfo8)rCsoOJT9%DAmhPTAaINKwvQb{zhIF^D3K#-E4tx7)umTNo2v= zuiY=ZVWPwv2hkRwpTR(P4X%5*KV}-y@wR(uGpNy97#tkVbS3Gg8k6X$`-lc2+z__o z$sXOdn#v=+}$dlfPsd<`OjR>cu7tHb zKA0J2Q3Nl@QGcjR;~G2{Hs){ZOtcy>93fG$9A0eAcKd5-@Y*;Pu8_S;n zet0#Mb(m0$dOuyQpX)D@KTI@g9_}=F>pTfcxU7B7M3+6m2Xy}Q$HM-odjddad%|X* zVHbBF`Hm7yhFr+;yGyHhVvw({8GWKd*29w3@YG_2jYLdD%32{MPDo4k#>;>EzChzr zkK`!YH;QVMB`u}K^87S1iBU~PaO;OHvSKdOlxoIX+L%MB$-;6FyGE*PTw%+@9A z9OzNdNR-^?$zPkEQ}jI9?omR2f`!232ATFqWh{kOCW94h*X1)LNrQxvV)VC6J#Vz7i zEiR*j%weVFH^yt^RxJwRw%ZGQuS{jO5 z2z4m%M)*Ogp+D*qHp&wOgk}S%ZV}KO0<%3u$EfD`X$CQ$n%QNpsKe(Kt@>0%^ZG*W_CM9=?Wva%(2 zt{5^a!5d$)K2{sw2}Y(q0&+p!I?oZnA3mgv*~4!Z&;uMFG=<5E+wmQJ*r!&Ph4XRD z(G~;%PDT;SM5m{U|GdWQ=d7N_zlE7eRcgccWy_^KGu^tG#7Bz-#3m5Umf)3Mswr&* zAWPjC;#kF9XrL5w^ro3Wp6?1vTOtR?2{n_sk7k?>=93GG&s8uJnF6ccEjL!j_Gj9` zAKiQXDr&)D(H9f20KUsCSuw^<%A$Y^{%guD@aB z;aY1A{jRHI@lW(XOnCeovHWJa)391#T?ljqHR51Wf2Pc9o?;_BgtQ(G!a!%0l|(wC z8$5XPTUwN*IUgB~%zU3IkS%#HmDwnZ+0@2^2)tLYfVKFS34Y_?e*06fJv#VeVZP zetE*M*pv*m33lHC*!E8O8~vRCAZ%vstja0l+vi-jUd4LUxQ$1ObZW4_*3>UJ1;`tZeM#6pkd8)8umPtM6;q|DpE^NK-IYK^M^?%$AfLhGBwLa z2upn`bRny0-WpBACnD0AM=)Jn*W!K5lgR zP4H$A-DN`t6v%XXY1O`IyA~kxL&rFi8C0c9U+CG1FRVgi#k1-M=)$B~{%t)DPoAtp zDd`CVG}P0`m=hr5q7pJ(?E9G)brh2IU7Nzm6lbNn7n2?l>dSe>E|#7*5itAA+*uBS z@z677>oGKG37x(9`{3v(iR-Q3omh8^=?2+X^H%b+ceb15+7r|HGKTn-sirYT@{3&d z-4BPaAUD@0oKar0XP+khg&s`hk)gGo#R810b)}?K`AZ##&P#f~Ujp1dVewRnM@}l) zmw6n9w@W#|4ejXGFTewH0|(b&9)$dV?=aazDthrddS{0JV8kTx;8t52^mu$Yz&3wz zfE7k82N`l0H!(JTb{e3Y>w7O*t?6`_d;|4>Pbs#9O*AiVUQba} zsWxuxP8q~jO|cT?O73BaE=DDvA^lPDz^!9aM>TWMcXY)vhF++slH}zrZzM*ix#O+` zFjTzN4rcLcPQ{dphM&}$Tc|FW6$~uMsZW%X&a#Dzs`~RL)uOzxSn%zeb6*7=m@t9J zmv0HPsm=BvM-_9F!!q4NN?4lJJx6jnqB2k$TfusuI3OrM7r1-Msf^p6HLsIQ+wLB= zE1R+ak^$0%>NsO2tSd?UU5pMC@=zzai2XOcqhd-1zPq#Buwfh~I*Uxqq#* z8&e%NbG(bJb6Uoo0_XWh z&#I=1s=9mSQW|S-bNX0sykj8tsjMB^#xE&tC^=a4wtXQmUEmA5pG-**S7MSmfe<&U zYyF(B%KOL8Ha}cHETbv7-L0*&Oy(?xPdx86_<)k)iV0zrlH%#pbd^pkRh~+tPorN?Oed`M->IrB)TR?^6p{!T!xF(# z<@ewFryAd10~TxPEOiy6;0t~Xp%x+=-#h&h;FrfI6@GM;2qdD?1)rN;fwKqSn>I;9 z{J1e?%EhgBGt`_FmcZNnjC=5{q@?xhXZNNr0u3(u@?A^7K$ZgE4=+sSq!S9bs%~t{CBuxv zHbvHsN$Z#YTHt4NuH*u`RC#fS>CU6DqR@Y4}PC3i8XBDdUC|6Z_2DBH>oH8>Ir zcZx2M7yxNaiP_#R_pZ0kidHGP3Mj!RNK*M2OlgY2bkbK@g0Ov8H9OnOE&#F0RsS`& z?ur}hYhRQc=mFn==aASDeHW$){j#%Hj~7;P)*p+em|^2()|K7ly`DDnJP5iK7PHYS z@P(!a^fFf|_HUS!nf@Qx_&=f)!@uTzkVv<~57I*!fs7Xvnh+l9r)xsA+9eW!s>u@t zyFP38_j-?z=m~ri>sMx-C!YH>)Rm;$GeJgck(UD`^9AUXMzn(*l0n6a37RMEj8Vz4 zxrUXe-FV;*Yn-`fU%g$v;Tvi#J#<~UXO~wR^r(?EEZvpXSOO`~Ed2Jgt(s)_{lnO2 z=;*s9i(VTD|+o z8!h79w1znXa$%JZm6JQ&a;egnw4`WtBaMxp&UkhcQ!QI2=oo(OWN-B*lf~T#Ba^r^Xr!PCk%*D*)bO+p4fRX$2W+BpBtR5X1CVEcRJgTbYH`5 zMLyPf%%DrD`*XOaf@IS?BlxQf$&=;*^7h{&S&4br$zb*SP2UFtlSTX&r>`3LzZ_U- z?ud5lxBJ>O+V}ExVJ1Ct($;R(FSD6)sve;~6v_;zBV?O$8|%y{_ky6?`&Bm%YY3OAZo2l`JQ6 zSyYXlcal2%yDOQSZ&PNBtP4l2uS3%ao=`hVOR@DHi$!TgBf>VyQ(e-gz`16Xb5q!J zl=S8|7VSBHVT!Fz7%z{nG)rn|(#M=ouevX*g`MBeRxePN3_R18>~qmN4;`+v;@OU( zLs^!R=Q)|Q4v@$QQC|yxW=@Kdm08EcPD{pt-M2jKUH$;z8}JY(x*9Ur2d~OWnCNq< zT1Xo%O=UPt=4{Wo7ETWB*B=nmr15G>emHrJZMt8N>JNO57ER&}=zProW5Nho@%1C@ zwD@gYDy^2|IIbK9FgYz=Vgi1W|=dJ$?8_h98tm4b~k) z(F<;v9qznq)R*WWMr;~keO_dOdaKBl%|KmYA)EH+> zdt#=o51(CtFSz9F_ZRqcsBLS>c=jXklMk3xFS0NKPbz#y149K6{_V&`_)QIc>#TWS zw6J3U>LW?WwAVq7$WPv&rt;|=40POU0Q%L3)a4$m5TToTkb;9T-VSJf?>jwAx&4q* zi<3LdSn5#D_Y4t7=gWmj`9mlu$n^fh zzTtv_iafr!+ZY-r&x^FWMs~wn`sRoAz6k}5nAnIZ!SL^AOmAP|UsR{0_h%E@YKdqw z{QhhApJbKwGsb0nxK_XvQP|e^m*C);{?^vX!UXxiq#p4EYcOa1bNFe{8#k1O zMv2R^bD(1DcG?5ND;sfLwg&Zf#rW8y-?W`5o$CshZO}0oKZbbu2dXr8o%TeZZ#L}u z-Ac&!+Al8a?=%L|vKsM?<-7bqtkf@NXzWo6|E{I;hlM z$-J8fETDM9Whghept6tecWo5)1W!-vfw;rS(yt%CS^P`hK99>Om^#SOOn1}h9DVWq zdDrd*{<+@D*>;Yb=DF5KpVK$Ag1PJ&da`ZI;Ef&Gr|lOACC8$yN-4OU8IG6WV0#6~ zUPJTr9*K@0U5VZ8&p|xC#U{zhyb+M?B#M0Q)$iQl%yPXn_;-G(z3eymrUuDkzsPQ* z{>L!#XRw_A=F44Bc2nEtN|hHxPKv0odxJ)kqdKv7;+ErxFZcd3lO^!Ku1j{uQbqRXD56oX#Z9wh zR7uIBhZ2(tgEUmL30kbluhdg}6w+nwNw zuk`E;?>W{s$ftiuRWG`TI-Za=Ke_n9|-E+W)x%su8L0Xv=#xZIs^9-rz%Ss?BksimBmUT6You zpU!jH({bg7k@cR}?!}?sz0y1A+*R^EpNV2_mJ>I#Jk8`Yx`Mt=Sk}+n;ubr=b4ptq7Rgl+$pLl;H&~zU{|Vc zxrSm?o_o2&=cA23oV&wfC&esXF8z}j6>;D^P{Qg=0Ljy;zt38|Kesh7Na;9O&U%{J z9wOOaBF|&lnqM@;wj*OG#8c+B>^?A~$K|$DCCBhnc8gyX5%igaHT-wMXCnV=%15S; zhD*0jeGWSv!*<|ut!T5X0)wamzTua74=bNj~GJn|0=Sw-+=H@A_@y=z~vh2lK+`zQ?Pn3iId@7i-!5 zRkmRF^NrX!)16}e0q!z(y}_m+DLgxy7EK+SrxX1s1ELku+*flZ<*y6wd{Jt~JXgz* z?eaZp4`&VkClj>F6Uo1olY8Gn0i1kkVnD)cCY=nT9Uu?tiP0+f6=r4 z(vJZDM{HTl^#81t`S0|sf1dLnIP<@)SursGfr5W}zy2!$>wlw{6f^zbTx)~YH(;9af}6qf$z!nEUrT3Bi zG#$TBl zKo^5_cE;Uh-COyFb{gjNr0P;+e>uz6#cI{d`wZ=>({B1Yd!>Bwcj`n9j6T*Zo4MD@ zGUFVNh5h0>ca>3m$CdE&ks(^{wMkR9sx;lnCdz>jBi5~EP35n7qd28SX=YWMdA{$L z1L!gb-o6Xv@vJ8#ci}6IEfn^RV&oXS8;1!)j7ysJ($+~0Ws_Qru>j|8my^Pg^5@5* zo%OW$54uK-H}5|CoQ~A=L91WHlE`4DrBSi1a{fuSv(OzGVZJSRn04FU!5>0^Wu2Eg z`GfXWsG$9y5)*po1MeJ~c&l0J1TLO;Z7fyatoT`KqE$y7SlT=Gz18(@RLwc~jr1QZ zk&6PVOVz_WIWjtgufIjd=zKpuyOmR{vX`T&o`ksBx9n(R+ko&ZKV8{FVi!B`?%$Wr9P|>%A0S z+K2947hD44Y{_5m=pAo~d^^QL^)x)t5t2gxWsNQ5*Y&|5bm<}Pnb=)6UvpF@U9(N3 zF_xk(Ph>5UobTf^LaglM-q|;0K{71S2lGbr&8b<9kYPh7x~bbjISpn^N+``tteB2A zd&LYVL`#RjdM^aMv)T;~>Q2xCr}70p@Nm#~c2@9KKy_lPg=;SB9;G&sOjKnsYo3AD zTWZ|VcSV$a^)RinaLA9RSmyI@gU6+Z-9@F_*X>o+IgCm_102wM$-d8RJmRhG{Fi5nVAXZ>1 zRLmddIxsOw*k;4Ci7;|B-wiGvipkdH5&vKr%EK7XOjE5cyskD8+MxC`fiC(L3`b%YReuH0B^(||g`WJXX zVH0#dOKOwEjxz}MhbPYX!QrhM@XZf0t0b>H7 z(9KPPFbE%3?ze-9^r=jLk)UGwyg~`~h+ivBrdz&7tRvy&_E>R^L9OI1$;faNY}9dk z>gc$w>WPV+!4QO3QX$$a6lU&^zxD*w4~!5_)pqEWix)cQ5sSpMz#_m%T0DhPh8JIP zQuhE1KOG)kzgJH^RA4u}kIW4xIEpw_%fJ8W5QG`m+8-&d7Vi|ydz(pb)V$CPAX3Jw zvwhS+og(cPfgq37RPjg#DU0XZkG%=$T1{7;_659|hDad$rQp_z-UNUq1D(a!H?ML~ z_=EC{Z`Aw@1_m0L(RWs(sJ&2l4~MeT@~w7vB`y4ZN_6$nu_qmmyZB4Ny<`m;MiK?+ zk|dVxIvfcQznX5?ip}tArWv`ioq0ox@IwMdq=HQ?R_e0m@ROSq;16q(Q|G2zD}xLI zOR2Zbv_x5AMMf!B*~Ol-BQFLfEIx)l89{@l{DA-%s@`7cZ;G50+X`7f!J8n`p%`AV zK)c7A2)7-*AJnDa^J+>bP+4uAc(lHcO}j9#=M?T1*!>JN@+y74yNnvfof#Kp`~*Eg zS;~{R8t4&Cd0SgP_{E5QeT@cA+wNG2=RqhmfS9NIApHK~2)!aM1&n4H3~Kv{{KiB( zfgnWD*JFB^)b&H&L})hr+Y|6!jxcsG)nz!|>HwGB5Yo&=FFqm&bNxI5VV2hl471Fa zH^CwISl}gHHemg%xmZ<54MuKvuCXGxHQnEHLq}G}a_%kJEF@b7`)R~~hWGHGHoD#O zlSn%W|G??EKFl+t|CI&EZ&`X@7pBN~OARz}Ibo%11Slb*;JD!2t(4E6sVRFlBVahb zr`9$@7go#WvEBwW>WtN-XDwXx8~={t`~xTfymx;FMtF^<1Mj2%st@Mu`W(+Uax6sg z_JkZ^vJw$Sw|GW`$J~e+Q~M1Vysh}Ly^ClSh4Dm4_e3lFB%wiE4B8~_CITz;urHaL zE$UCm!LI{tbbM%{SSyPDJ$|&;`ic?tm6An=AqHHIbwtW0<~?F+RmAVga0a;j*#Y;@ zqNkXrP_USuO{CEZ<~yGVc(Q>!sbgty5{vsKnhocK9hFOLR9=zwf& z2M0DbPAJQ5C>gGaCxr(D`7#V;p^yUJK>V$^O{Q$B$GsYl!O%Sa>SmPE_8khK-$QpH zZd3HkN_4DB)9vH^D%3`j_yOOV9~J*pnc2)nKOVay406}GhhN#na%*m1x}X5FoinuZ z1GHmTE{vDf*K5>RkzjcjuYJbZ7EpyLSakt(Q=;&(SFo)qGt zvnKO1sP88W2Umv8IUOtZFJUyE6svbvzLBwBj<9;oh3Y9Gcw$r=ELIKlAk34dX%FE% zi;qlNlc&jq#*0<%$8_d5M5F>y%IEgkc#uPvMwJT1*R12WwjABa_;!$ytG1{m2IXyB zko_JKWn7vYLoz4bZVC!&#=hn*9`0g)Y#}tO{jh$UGs(x+bjR}E&`x(j&A5*dXN^qs z3kEAM!?hd0&l1%d6Z3V$#*BzvT#D>cv<;RB-NAj@?A@0Gv(g1aU}IZa>--_@;h{T% zRTORd6WCocc;z>7u?RmM5a!&=2r+FBaLr+QdS)-19r*_Whr+yJwL+^_xCGWIZ!skX zl6hy5(Hc-i;Egl?sG7(@jG0pAF~!&eDtW(@`pLAsqNgwpCufiSiW10cOJ!Vs41sG@ z1#o1{M4-`VhAm^uG2UGoyBF#zZQSY&Ox< zPe;NIw;(Rc=W(E&U-pU5181Q7VFO-iNyg@rCqzxSC(p87gwY9RD^tEQlzt_`w|aPu zjm|pJjlwg^pQVO+0u{-|w=M((4P2cl4Ew=FsLQc!-$&}&Dv@9i4vPGrp3y6q8%cG^ z`XfkKayR$;?V#;o_VlSyX6Sm+bLC18%mNtV6%A-U`V0+oEC;iD+)0c&vipsVp&{h3 z_LJBEJfSUs?JHj#dN50y=*dad!{HoySNlUbd7AQ@?e~ctVC*5x5bO1yU)VIHCf5DikZmy-)DUtv^ z4q&_0l^{h_Vr4qtABAox0W}&QKV?wKE8IUKvY|f%_hi{bxX-0Tf6~mQmk3QMbTwYg ziRfkFbRwd&{^W||7=%fA!u|cHU&an8qnJfnF$0AQ0u0*y+`9W|*c`=?%yH@wrQ2|* zl;SYs!b!h(W_>hyJ!!?;{&zG&gN3KL)HwPvgNzuygVYwWkV^K$i;c<#JAOP5(WO?h zmr$1mXJ-|*z#M8ch^wvf>102&%ePi+W70LX*}T&g;_QcDk-KoyyE@yv$|umbCz1ui zV6Ie+lH1AD%kt-q@f9B<0O44;7JYq^Yi#Q!n17>0CWnn_Um68#KtaidnkVb?D&)0-7Qk@Xj+D&qE+9?hW)zsbZI{7v7B+ zj|A@&wl>c!p@5szAibqc29UW76w%2WTyG~*9Iy>D_;?KckrtLWmp4G|!-f0?dx5md z^s$~?37qKAm@#G}h4+^WQG(u}0OQYVF+kALsZyQ4%Wei+KZOW2sA2}&e=LHoNZA@n z;#C9!cEqgE+oD`v{R@gm>dW;QM*QXQ-=XfeLY^uS*kL2>-AC&iJP*F_4tZ7KANYz= zJ`gtmwIzqI5bNz)EEnw`xg-?R{|{E3jTk z?&$Mu4wkL83sq93HZV+Gg0@vK?+mirKZ7bF?`tV5i%ug=0sp!h6kbMs|K-yfhX?@v zWM}1xwIN|MJdj_NN%|U8<2GY-)i>`-26jWu(u4Qf{qm&fP|xbb-8>0>t}15l0w(n% zbmPe$9}~XLSxSsw<)7g zc%}GY)__t)hY!9Ht^P?W$E4_IQWEVW&4Y2|Yc}lG7u%gTX8i2t*O%|pZM$hQ6O*aQ zR311fIEzzX6{>Km z*pp1A`&k2U1?N36qYSb+rfn97t%3Sr1GhBBL{H_6UF{smd zGZ1Vpf4BQW^ZG-&=*#v{3W_+2$ANjQy@=8@P<1RvWL}mkv&)HX*`L$$J{Tz4bCJc; zslEW;NHYzVcm;MxksF#jw*8p~79!t6JX8~%OedO{QXBU zQ7VF2A^g)BH@`fGsgD+qs6QnjttX|zQIPO>KQHqs9MV!61RDj_R0|L*u94PW7Tk#% zqnnf)M9Q0@iAZ(w#2Vp+QPPIJOS25{G2I&#C->e7N}Gzn-Kx( ztO|*$;nL=UT5$!-JGKoJj1Dr-Qf7uIU|kqOpvx7#fL0YCJ4qPd|G+c6F#mC3%AeY) z-;e-NZ*mC1G1}q|$8ukYOJywGxU!1uLSQbngP0CI4@G)aQam4;T_R}ZzhzP%(l)nt zDt$P8PXl{ok0!));>iK}!f{Q)vzjR)+z{u&pe??XoOWT(p{;<=s2e~6agevc;Karq zsPa~0(It-~OG_F2I>(1CJ$H=mktI7nrKiN+m{%6(jhLnPtA08Ob*x)C)FZM@D6&kN zKclLQnl#VU(2NFs4#gwch2B6Wc|6%tn{F$T!9Fi!YP&V`vS3gte4TJHmBp}sMZ$-T zcjT+AdMPFqve%h-GDPZWj_#E@t57#}ila{EoTn+tdjudW-A6``cYd7=96^8K`xhb=(o?YaCC>UK~fbv_9-IRZ~`$A*LIe z?PTH$+$Y-8t@Zz6?Ja;JYtnUH+-ck$8h3YZpmFzx!rk4iai?+j#v6BccXxMphg0+a zM`lh;>^=9!si>%kT(uSCvT+StS=hIK3$!z48k7fG=uKAoTj{^ z_6|<;#@CXdixsP}u_7Kd>|IiEf%Z(`AILJAtm&+IY!b2cRx_*2TE)1EG zE>T)7)tQrVF5nT%EEFhk?skoB_@-TyXpUFMxVMg12 zwM1IS9kVfXTy9V4H(ho-BX0;&t!`Yhaq;u+5-=jFCOflyKzxmRkI&qOi`kO9IJovg z$nL}1c|`^cB;R6q5#8+(fBN~3$zRP%h0bV6D*U>VRZ~i2EBv;cXW^XulKWC2t`)lQEn;ECQgek&tG+?vf%`ks;_A`t{p&sSUA;$QF0Q_Ko_%)p zlG}t^H`kfji5>3(S3^FQwI+n6@Vx+C_Infu4QDl2Lnxwglm;wq&TqafT?N}i@cF}M zL%wKRUbBo*+S!3)~cc!06 zw9?dZA0_CtoBFCU%F@-OSWJl?x4L(DM}t$j$e6vnN^p2NKzO4usinV9cny0MYP>tQ ze6H(qyjS>4(t3Z(lxAt6lr<;)qQg9{V^zzt6NzyLek9A>Pk|b8soa$bd_~VJdZnIc zhC;;4aUaEqr@a+U4UX10B6Xfx1Azz~qr`H0HZvlkK4ne#4;H6Sy3BwtI(gY8B09h6 z*gI7?=Du`)L9U3(i_x2Q!tH6S1{@=w9e*(k0_S*iW{=~bojs0J8Y+7-cFD>vQoVyJ zzY-@L6*wg1sfbaGsorG`SVA26w!|i9sh>DV^I4#BYw1vto-4$vb?GxT6vnmX1fqSa$;?AD#@vd9qnP~-`z zZ_N-mjC8m=Bzea1fPQc7!mmqg(VK+n(R!KSEAk1fUi}tJBA;X!my;-S52ewWKq z%X{|XWFa9xi}{e+67AwP6YQb%awm5&Un`;X*k{A(az4|nEHe1ze0O)HKFS&m?c9c7 z-(h2_)YvE@^y)x=JdFd^8XpyZj*6*kb5j2(tyC!GA@!moh`}~pq;h3oz0(&O#TAPr zw^&yscQL4-L;coGC+OF>GkXzq1{$872c4We0VTXWxw1pZ!ylQ(QBUID^HKw{kUg?C zwqBjBo2;a5VV3fSxH$39Z(_NDw5(oA!K0&aI;k5SwUmiQm?k+LHz1!*t}hUuU(QR` z1VOq%0^7#dSw}T*1!SPyZpX6rGw`E`6B~ng$!77kCy+_q5>v+Vt~WABo>Ot+6cr%} zRy;LdxE?han`hg)uYU#27_;i~uUih8{D>EGJwj1;e?9p{u1dnzz$9ST=IJ$E>{Y3x zLcC&zALGK>Hh$=f>0lQx)hiA)i)XVl?Epng2M|ATgrXV5SPO9eFk1y#3S5Eaigq1 zut|s96n6GP!29GRfs|J)29{fzlqw-#t~>S;-g9@i-QHe=G15uqtI-+R?mAChwoZRY zt7&kP5R+Fze2f7kKN{14qN0HsQOV7e#<#XdgyF^=23$N%;jF+XFh)jn?)i=kliqI= z{2duBJ3%(ZmlVe_9Jf3xbMKHLf$YN>bF-s8f8zPOMjpV2k5rjy z1xpwvzcAB+gI}l`GAV(tO*O5>J(Gg^YRLdx5B7RKH1uPqSHJQD!uBB5LM3QwfDg14 zx1@=E6;zlj95_-sAN0g1u8`6D)3FiT^RZy-@2fJ$KB|Hf?GaQu#+sM#RXu!J=jI`@ zlV{_!^htFFGKnfy-MY6nIGT?7x|61o(Mm;963|#?E2%H3nCL#K(Ma2;Q-eWh;4wTl zCbD^^p1MjHcK4v8R%z@NLEF*CA$woS56_+Ym&^j1N_#mdLW)(J*v=Ao}8?9O&` z)7TQq$C9{M7@h*`3laLNDs~}b;cF)(EfNQ%EW!hWs?5L4zW{La?N!&L;N#4noMI1g z^X1R=q#hYtpQeJ=Kqx0T#l3C&E(2@`d_o_q6vbU>eNDqGn4=)YaVyNy8$w2w1T{!+ zFt1r^70ksv=NHZBpVCR_@tnS1>UY3>K>GpwA-ld3!!{wgL2@C`q1q=%416(M{=xrL2t)@zYKp!&-=rEG?{PqiB`YFH$JLCbwU{Q=AYy0KLMTz zzHtoW>9GwONvm^gIn^wL zKb1ukd&`0P{9eDC0^cQEPCsDI@bb{YleNGzvB#{D#h7GB`yV34lAvhI5k0+*TqQFr0`OSI%Lb+l}o^SpX#<_{QtC z`*i^7x-dokZnf>J4YJA+i(bwq05mxWA6QjvN9Ic_w~Bx&Gt-U~-#TvSl%SjXEda$G zj-z4D9|`2{>+V zXZUqgp51(<&Y~&QAq<8WYNr#pey{8TcM+&&s9bFUnuW|MZ{b8Y+^^<{`!JapF9-Ps zKMLM7Vhm*GrfI$3v1=MJPto_)rF23VUW#q$PL38;hzIeCi0|>8p754RdlM>+XTiwh zb*FTNR?s8m5odPIv+{$}3>az^UEIN6%Ka33ZA7)%PoN?xSCV(NdbP{gWo9|_Hp0&5 zIj&lbpIqxmH0l#6i-q3XKCNFqA>RzG!DYWaNmLB5O=nZ~r7_9X$oY**#OZ>rf%kFm zEZ0U;myckJlkiO2b|K7*^0Om3tCv+Xq<0^n^b>ohWKo=7VAsVB%GG=;3?|1NH!Hyv z6U(FjV0HpSzW+H
      J@{6kddMlrjCqd)}7I+LdA+*WY4fj#FyAV>TRu}5I^9h3ui zsQzx=t3XchafWN^N4Ae{MbQD}{oO6dU9GohyVdvp4brn#+syF#?bFVxn4SSxJnFNI zDo}xs;5#XIiiaZ80s;Xcvh(_OR4VWbAzj)t?N)kTt1RFo^B$LmL#bF}S-Ss)p=G`) zlW^*Bs^aKT-P!X5yLN3uzV+oniCJz5Yt;L-I7xiGkbhN}Q`)mO(O_QyZn^KHq*I9U z4jr!kd_=PPOFu5eq(bwiRmj@m_$Kiy%|2xs>CF7{UBa05*YlUh6OvnifxJr6tV}Z& z0duG7tXVEy>k57arCz63=0#c7mk$SfcS`3YxKw@|bO%S&QTiNX?kYEvqMAL3^BgukjlJH)b)K z;Z@5Wr3KR;a`MbJU$kS`XX22)ZXEBtgA;sHIfLX`f=jGVD zhAI8&!#45K8~nj*RXg|Ax$Wir@=RmbOWX&PQ=b{lgT`$vraV%a@ttcyGOnvI<>EA1 zED6?WW3~sL@i8UJh5=#q`GcJ?)=69PMe>JaX0~2Sq|U+X6wxREnFU5rY^XK>E}@YM z*1KhxkkG-H=9EewCC%s&eoy{01g-=`6v=Ju z75Myp)#;=n>%Qu(s55DM>Bsk8H!wsss9E8AHpB&V4~%O#j1ZT7wxzmY145^2Jkg4|yC-b!$1f8`x;gNY-{g>$yE?ue8(y*^;An_Qm{J}1riiS8^c zVt!T<-9OBnUZe`ZsmhcfEgcY6DNfHYz^}r1(w)c277`Jk88CYt8hC*FeaeCMU`l(! zXw#jMoL#atF9HJj`q{cEldH&Y)c6O>0|<~gTyuQjWzjr;!oauE9}{Y+PPz`yNcfp@ zMa2mKmo8%Lh|cg_dl*^^Djf(-$C_sZhe2Cj-;hu+J+qkoE_yZUZ=d_c8OH{bv5S;N zdCmns>8Eb(@1MBM(u~?hnVe4Z)qF$IMVrVx5}?? z{A$g9?b=Vwren1?cG*`VEJX1uS+iW9dVIP~q+#mcwlcc*lYwX>e zo!B+0zFV^}MB~MWWy1oTbF$QcJWaBP)R*&@5$+d5Ky%C;?P17iCA0S83fo+>Wfmvy z$p*&f1^&Q}zH_2xMFZ>N;&a**0X?#S2=RMA=K!Mdb$yWiv19S5&%c);t=iA!k8DvQ3>$P!saHx;K(!mq_6^&qzZ$#A%iEOtf34(vhV{0bVx!*+Pn5RbF2SkoeS&k-tYM@O{!M)3F zX{Y^h{W-~xETBvgrGA+YDup_Zp(j1&>drC_`3oZ951V?XBoR%!xqs6vs;f@NE7<6z z$tWcHPanvRhRb4z16blqW#FbCpI--GLXuTxxb%%M#Am&I)$Q_-4aYO_JiK+0Oe z6coMt<1g;CCgCqi+0G(=x4i|#?rPn);DH@qoDL<=BY&TK0Swt!*hkyI6i5IhqPr3O z@46B9{g4t7$AXCNNsm^m)X#+v{dzuGwr5k*k%Q$WdImF$u2UX$-7Ce~c12uC)=->@ z+aK_@5O#b)O~B1Vv%!2oIv{`dK(~h85eLHiZTh+TQDauZes*%e4S`aC7k9Wofqd3+ zj4^CN+)3&|USaN(fj$-0le>84y&Ve4_dSLsyCP#YU|Xl{SlKs{d!Bo2Ne8axyp6+r z!T z0zGhFx};b!TLI1TUP|wolOIzyK#C6y{JzTu|)e;=OO*XDZ=rqBPgjm`XZOjkn^Dq_9`o7fb#wOImtDQq1zY2vs3oD<-_cSd6EkhyCf{vF2r}-Y$Dae&7}?t9lVYY zFL)xbS5qC}T#DB>AJ>x5)W=?s#QQdQE=h7tK9m;}Sd4zBTGa+85EYZX3`-HJZ%=qMMe+|-;ZT1P$DQ0ndzd1YD0 z1NJ9h-j0IjItJVHHap8)yvk*@;dSCY*8Diyk~YxAC@rxf@itVAeXdQ$ne# zBdowMd!nl%K^MREuRqyUfuO69uq6L@YTgF(CSTDBbLmE+V}B6Y01nb`pQl2d@(=bU zh7D)C>IRH$47z#CV9};i6RcE@$mjS8ccFf^Yu>v@c*!1<0$5KM(cX`PV4s`rbrY+L z1KH!FzGa(>@$CXz$$Sjiv)WD}UM`-AV+L!)kKT3PKM6fPY3W(SyG&6gVNNC(%defC zBsV%~(ahp%lGXe^$>6cef<1^YULen!?tg%GOh1}A63e2V3h~WWb%}hMc_Gw+zo#3? zfO^9k_uayr$~<5$oB+;Tp*O0n0lb|RY^V)gLK=LQS%+6?MJg;vC9P(8=a*467hJM2 z&RLj~kNdU1_`IpcmDN(SkKgSvt-&_+>1C0HK5eSv3=NsC@b?7Z$|16Z-n57AVj(Ta za-7&)L2OAr`Oj3_`y$SgCh5KRA~=-Jowi*)Ax^U1J0LYts~IB>4?3lYE*S2WhaRXW z+9-v#8HGNyma2`e+r*yJR)$SsZI>@WHC{vA1{fElET7-JFrvht2va|4p89UVGF}rA z>xO(j9AX}D#3TtfTM>HXD3ql4vC@jOSbP&EG3*|aCutNyvV@=m0R4`rwo*j?5GfFt&uavY95R`AsP+Egf6N&F$39jxyY{2DN?C{zVRcP|5 zf4+m8-hTBU)PU?bO#HS|xhDLcD9NQPF@tFg_aqN`KGs_-zdPL5wF>IhNEJUOx-~5N z3g?E}%_*speM-?rZqfos<_ zAf^LiS9*aL5fkGQ!twfpNlNd_UMr7P(7D()+2*9*gyAGnc_tepZg26N8>j$*RsH+h zrR-cM%xyd*{|ofV_iyVq6~GksvTF~$cDnf>xwabl5#Fvj0pX@52GR7{W9XAEGYL#R z&t(smuez3mPA`u6iO-yKNc>EOTkvfZdhPIrKBk+hS;{sAyz>GFSmJ26O~A(qB?LBC z7%t;}sGpF@zWVVk@Y6hr$6ggk+O&EB?=caCTU_ zntZqt+*R+$lOTzJlfjrwwBB5reEdP!p!Jk6CF$OY9sD-m5W_y?lP%eyUihK+5qW#{ zvH5H>?NsD-*el?w?{F?sn4q!$n=Y$fRtxSjZjjum!8HdA`kRGx-d90aUl{HuY}(am1Mm4xP64fozXD zr`69wFW(unblsBQHl71e&}s0xa(n8vP!U*fCN~`)>ywh@vL+*V0+?YLyY?w0uLu(G zhWLSeSqGyRGu*JjoF_k(ysDs%v!`2jku>SBI~wA$@?~{+DBno^?&zdMsfJcG%^7sO z1OWlVNx@h|U6S_2DRFuXREN3%xQtMt9&a`+r)tf@L{DQPU0eqDrRO%ouV0k%YOM92v78*j|EE2SOs6WkN*6!D^v6iAJ~ zh@P{~iF!?f1dhh?pCU8cob_%0L{JhP2PM&jkK!glxVw<1o#fo_zACE#%u~QI)(p8* zndW$mnwwIqhCksj%ayUQgGF+03Cf!^`bl5RFX$mqIDaHR!!DdIzj{Hb!YvoSbcMIEzS zc=u6IfQm{Ew}ve1D?R=tIe0mOiUNJV873j~BjdD;5w=J-+$c~Euz5e&ql7LrbCND< z>`pnMf&!4`F2kK}-YPV^De*U!;lo`V!(0m|? zY{tYL=2Ezq(YB-=>w3S-od?(BlV;NW(u?DYsH^?19q|nq;3U>VH#0^mOFz>` znu}>}6ekn`0i%Rt3Xf(9`~UYHqmYo35_DuUK{Mw6^_8w>k@V6XOsGhVlGhj6-lcXB zwgn^w5gm-cpNkkX6qQd(sz3i+=tZSvZGySPN6OY}qrDo{)6oBsLiJejINX6pKjv3X zgQUXT*J2ygITv;xPB323LWUUH^@f~{L8V{QK7E*>4!Yq=)Z|8ZbS!J6y>zI@I0zn~ zPbg0?Dc~~D;vk%$$3nI_cvG2*N6aq4*HfuyglZ$`14Br<$v@K~eA^MN&#tTv^>?DI zI+_d|(B?Xu^Uf=dKv%z6SG#g+lH-w;BvVMY_#0>S`$v|Ut-=-*=UJCxABHcfPN)cS1Q-zH^=zX0Vc^Cx$PMH$1xgD9=x=bD>}hu7w(BSoo*BWuPlPY)FgZT~g%>d_3eoeO8o0n(0sZVHA8?mR<`h!VSl zJRGKtz@;nt2|6}`E}JI6k2Y5Ds3Lf7+Kduw<0!(pF21;l4aH4vPvPJTf=1rf{(A?P zi>J(4g5+Z>ejJSUWBi4o$~eH|49&sASKLAXcA+bFVQ=INUepXkKHCPBwPC^lb|EKr zVMXNcXa$K-vLTeCD_1W37ExzAXznz%)Iq-Ue$N+K=j#FVW8nI}F;`&x86qe2st`epM zqCD@$pMGYGymEewP`2rE3DBBus1*;kNcEM5hGdCQU(=Ba1#m+}pF@1m4IB5cRa@Sm|rhh*uSrZ5WWtYMqd!P>;A zTr)c{3GE-2OW58015JxC47P3MR2-Oe1cv1BmXg&qc^V5!HBPNPsK&LCC5AX;nn^$O z!)i4WScoE&fcaQIdrU>N4))sEk`m(q7ddsnn**4L@TtoZ7UKD#0+wWr(-I?+aG{J> zFRim}pf*--)Z5o2!*u#=a4K|0R!;s1?_Whca@3*IK|^sp#DX>nsIz`l#8xzW@HOa&4f_q-n*cYKd-f=*nK&nT;Cq}7~FWTq%CT>T!F z?R-eb7C3$5^w4E_)n$Cu1-RXNv^pX@J0NU=B|MuTe8M8MIwj=7&T3M-$}!xRS5a^AfQhKY z?FI{%h!Gp0L#92Qa8o;z{_{E(js^TrCa@LpK9{p6o6%l^r}|b-nZb518}x>FFDs7n zMaMIqR<|<~AmThh4v-_nztO(Q868dtup1(ObGksE=PI>F@agll|KUJApUj7=^EFwE zUS`XV)VVcH1jQ=cG`_PNe@C-m8%9l(poNxYF!!6?gZPl*F7$2)@;yW*%m?$gWvm)X zEBU8Gl9S(EoOtb~XRrzYbG7ZIola^YS*s0o-~P`;aSNH-i;s0Yat>8Ps+CSzvi;Cc zO3-X5YUA!RcEk3~7h>Zqd-ba}JaQvp*enCT~{!lQ(WVIl1N_)LSy~bgxo~4lHOYqp=z?h#)U56_^^k5f}?>c zgJGy|^#~Da^tZZ!^*Yv)Y4qjOgQZKbRqkkyLc@CEI@sJDZ;EgFyq>%EWe@bgqvR(! z@Q~x=ifIi#bq2Pz78|;GAs>BK*$Pz3LMY<<)=I{!nB&%mBSKPsP#IWR`LN+qCw-k# zT0zGpRh6P%HHo)MH<=x8P^i*{0RI4m+o^y)7Ar2=@HkeyI;nTNDh+_KsO?y`Dolo> zK_uLu%XZ&%zcpcT2ZjO>xSTlUU97KHczTb+&5oFS!AQ}6anNc*=06x*?D%%r@cd;w z%(`se-()mdZ$Y{1n_U+{j0D-?giAAlKkK!>#${myLnAyM-GCQ=P(`!EB-m+GdkFvV zs_10pZP{!Tzv*SXr=dL2nn(4gQre$a+b{Go>&xbmpFB=##2*;Pxc>#vKo}p1I1FjA z+R0y(>OkVh)D8>mr;a^XqeW3-cDOl*06QEY=^2L&)lYbds2VyJTA`J003!hFp7NT2y|7=3xv5jXpxyvopB z#9~c)$cljJGL1uKmN2dUYErd&1EapGgHgjVR4oF`=_286+l888viEK5$wc(5X_~ZZ zHB~pQ*|IbSyizsTYoq3|T8nCX*`ANQEqhWW8wJ1%F2NI}+3;VsITaGbi^x z+Iny7>IaN%jvRC~f8C4y!HCvXfRE4a(Hzu+2-XJ+2(bwYrR#yCiF?b>d#RETO%G9g zgWOisCp2`V$FV;{igpeyddKqurV$O`Sd$cJ0(AvlA)TSS$UbPTp~r3iyboty<$mg) zJ+E%qAJ~)ovD8TGaP_)N^h(L-#t>m>pm%wg4FqgRM34>t+s73D2}3UIX!sAT1~(Hs zqo}^!|Dt9vF)=ZIGyeN4dKPA8MsX{BQ%7QM4n}cX8z&JFTQ_Zbb`BBEbzs!^Cu#qTq5Qvjo_`@Y|2h7V`Trr$la1-W z=Xw6U&;N(`$A6#O``=+Yb^b~CU$XvtXbcAv=RZd_)~T=B;Bg`YQS?`F5ao!Kp0HEU zhj19*cX%umi7$G!^7gHr?CWSLpI@^`nk|Q;@Qa1?yLK3cw^M-+o;FQx_^4P-N9)Q+ zO#YtDpyp`DQPoUj4eMm8nlM_aA!TGSTy|m~i7eMJal-ku#>$tGGGB5M2Os& z#$GMo!xFiHZCzfVom}A+w6y8tIvg**NJFeBermz+mGvcvsu&rO+PC^~B$J$IGOKPR z7r)Gm7;g47iM0{K$RJoHCG}9M$#&`GIm)nE<(mF%bG&?6v02mDYI4!9p{`_^5eJ{X z-v$TWElaSjLQyudWs0x*OH?v0_B4+ zy5Sx<)h|9@1AgZ*rS9kngX5igtya6Q&zEbu`czxsHO_y}prY z_h2jNTVKZh%!qS5N^5=p(X~~2{MHb)M+xrOaA)2G6KxS8W9PZoO6V-_550huiZmg1ad`74|y7Z?e8Py zvL1_8wODi1v@^ujYsfXouV7bRNdMZEBEST$MTEZrcMgNJuh6RPLNXT?&TZ+ssH33> zzeM|7Zdixnm85a-Gs6r^F;X=hBYtzE4JG=@7&Iobn?tm!Oqk?ZH|Z#aJi68sDbvSy zVuGlcElvs-Igv-fJ!ncP1$t=!GAYdP+V2YAD|b8o-ln!VwMWBqd;Ya z%Uee6FGzc8;DygMQ+!0<6ceskQWx$-9jD%VJFp-p%}F4HbSx(w)+%M7;fX&l>Fh}oI zN3@Ge&()oP-m|b~Ljh52?C1U-m0@f>E#k26hC!stq&{44h{!u4-d308Yfi zO1N}f8kS>f5YC4g)FYy!kFpY#93GXCMuvxty;uR?^E@k}ttW}PPRZ`U0URW_Qq8WC z5jS_+cw|@r^d?8%PYlb`d>N1UW!p%;rta9V9}elJLf zQ%M!AXT{&2QtJQaWc6jb{7M&08f}BD>{>c8OD9;k_=jBYFrypAq06w)X9p*n72hx! zWXv9#y`pIAsrKTjt*Z)>1A4UPZ1t^1>EZ2^e{8FDMDRB;fxajaaU=~CEr>9Va_LN| zcj&egY6AX+%R+!663GCMZw`PdV^B^^^?CG*YjS)py1dXaM#Z=;1^0KYBEAt%{EqgB z$;laBMr@H}8@?u^9pXM3^csxUrTK0pXtP!Y-BnQGXv;1EuxA+ICZU8w zq{G?ZPkL$rsOiIAc4aIP}ds%3b==@Z>M z$D?@{!^yHK4fD3Rlr2vw8&!rnOlMxiSP0;&y;@#o7W)1PWf)CJYqJA%m{#Gpc7$q? z)s(=%@}~>|J&x6>8B{(*H@L1mR?1yZ8s=S9pUT_L%`F4g)K}-lwLbY0_8i0v#kx_ounlRR#}#xO+v1 zUsZD_5@psV@(QRg?K)m?G4|bbHoZysfr4x<)Jp%mDGBpGG0gtr5d1aj{>wQ07is(d z5r+WCxn?3(V*D>T1b^-GKS#*_!yNmYtIYwV4E#Nm10ma-z`{SK5la6cZgT+(euk{CqkTk)t@{=Vr3#)0ORWyvN;rHzDEJ{uv!3 zX%aa;?~q7$wKsP|{v7l1bn4w=r&%$7c}zMP@R8C&x0sz&>aAm){t>4pz5Y9OQS@c; zrpQQfE2RXko=WGS6gS`k6$P6-ne-**a@FPfv>?Q$PRVzO6>^JklnMz7~fS?fAMHlbr zN5O>9gQdl2`OKL%Eg`JZ21rSbU7$*qDyYp?X|1a47ZDG0u;cFDa+6dBsj_)EL8t|y zBMh_iS;(HPW30ODoDgJDDkMUEqoJITcD7X%hp-A$_$ekt}!DchVtt9O(HKEiM zd@Aw!4U|ZYr9y=ucKPVesaz>n^zZWe7Z2lxWqLV;4V)oRx`d52<6|Jm3Vzn!GCEn@ z>u1`;VN830Mv$@rMs-014q^uums@d6y;|Ml=+h7OtC2K8r3bz+;RmCbCxVx0s%1Nb zslqeJW<+B_bq3K581`F=i)Si}@e$30tGmH_ZC0yIqyd=R8Fz$z^{K34?AHquH>Hxg zolttE$Mb`1Dlkhd^-Qt)ngkE8zX7+bOeAYsJ;NtO%Dj;le8ps-qTHg9HVY?qDx$ol z6nQ`A6&7m+ZA@$#P98%NdWN}0v;;W6!xd>-$o?ReI@fMWrLGd{k5ZcgGyd6VT6eO# zhAj~9C2zEsQ`F2Aixv}xh*%go+wOrJM)jKSrc5pTII?`>Vo3x!uV2K=6q0y zCl+<4Jhio`KoJ{xtpoy9GWa2j0SZ-m#1GWOfXzZ~b+nK}33A(Fc68o7jzed~TYJ)p zEu_ia;NN?xZ7>k@g<&1q;NiIh{<-1UujG@3h4mtjr^K`2Qk%f1?fb>P8Vg?tFNt6rA%C<|<3PnjqI z#4(F-#_E>%+S29rp;SijnH-`L5L6R8t*{C?+k&XvV5V+31`CyPWhqdWyv_wW+ndgK zLZ9!{T`ml>5l7pQp%G;^7Np@tglq`k{Pc4IPPl&G?G8PqR%2#n_{CzbNnn%`uKTKOx~L8tB@5$mkhdh+^3zeqqKO*DI&Qi9^JyyPm^t^ z+NZ&slZ}_>H6>#jia*P;;G}Dlg2aEDA9!qVAUZ1f4L^5NM@r@V>GQS^4WM%PapzoS z)2ybk{wIGo+zTOg;g^QEK6Z)sv=*yNb?)P)Y!na>#T8O}U|Y6$|&u z?cR}*!x$rlL>B+i1aEF7$v zPUq)u)=^NJVowyWEcoWaHjik4xVboZhLydvh$f+d<;h{|Y}K*b%z%D#KzJV~N?#G8m`aE%{LA~&O1zil4V6#)n+pe7D2@$J16Q`8 z*yfmm1~G24Q}~Q!ulnm=?>nLD%LPb;X?mRZ)6$szGEGd?qRJxuW=g^V=qq`I2z<{L zI8o1L?;nv}e-aEEE{D)Q?K`hHAJ9zvF_K}qL(IdU1_PY6chq4tIDFF{#_oL+n|g;b zncR60L=Hz_VhF{Zkwv%uS~!EVN_=IVl6)`$ZYdz01TSVJZMThe@s3|t#-OooB}q0K zS?_@-p*(SSHg<<#l-YU*0HcrdRa8{Q#>P53J9~P1>g(%^ii$Qj zH=&`Sv9YmDO-&gX7@(k_aB*=72?=d%Y$_`&V`5^yeED*Dc{w>b37p4dXJ_l`>iYQj z$jQm+=;&BjSm^2L#mC2g{rXj2Uf#sSL|$Iez|a`D1ZJcxME`H+oBt8miG}%JMUH{6 z{zK%)#|Ka$P$wxVDNx3@Z{L8IL_tAub#(=5Q&m+3x&Rc+%E}5<3)BzP39LF15s{#v zpq7@Ft*tEq0Ra*c5>Rk@dOA>>udlDVx;juZEG#TgVP<9~P_w?iJ^%m!`T_<9R$E)k z$jAr*0l~}53lt9&3Dm5tto-xmPfJTnGBPp+1qBHS3E;9F8XB6DlT$}WhoPaNn3z~Z zL+twCFg%@(0>-n%)$0Ay&wt1{QvX$@O@aew>!xk|Y#m z1O*=4a`?M-Hgj9W;n$s8>*nVKcy=7w_y( zHv0t&;85Hi^;TeCj|e}cr-x(fX>gRRbJsaBI!n7UP6Y#81Spl1r>&qo6tcDS?X(j> zGkM=ohX1;}}+aN5;8Z>YCD{(-XY@$T$=lvrB2G3?^&rk8iG+ZEoHiFMVN>?_e2u zaGxn`281csRfamI|Bn7`Q<6eF&DN~_8->_%_wAMfkOsVI$4khJsF2v;Tq>%Ca4hS| z^QAJv$ujzPbi+{|Ci&uWY=*Xke4ep~H?8D*U@lQqesVuuATVM6_xmntBAGmw4*%r=U9SPjs z&NjOjh*NN1ewLIm!)Z<+7u0Oe2Uq(K!>cK|h=$>a z9r)IsE==$74;mQoQ7eNF3TFImx|1Z5gC;bBrnllOLQIJ_FG}uZnRoO&D#4prwkRRb zhLC^@(6V9Ti5kYRv_DoZ85vLpD^uoXnW;{*aupcfj)2K+H)`);q}n!{PgjH|RQEFe zH#C~wOW^fIx4qJz92mbEKK;pb-${OPaMBiKN5>mI_Sbk2ZoW4r5BYf~Cc}r|j&{f( z=L4Y8JRh-V)}s3BSQn#`>-`O?^Y82Idxaf+Hn-UOjx(8(mfNFJ(K(DSRX?yC(-?<$2Ios^}tHY7&^IgQplf&!R+07QM+d>4Z zBaKkN##uzts*akM{b}`y^cinE8jT_5R!~Hhe1ZK7F2E*hCi9*zLabryqgulqsSST! zC&j_%tfC{qLAUwGb)kdF_zXKBTHqC}D6;EqNpdWP{sLz9eei1kV0r>Ixb_C~Zoj+@ zZ%8g$eBxzP+uNR^S&p`&sj*$igx9)ad1qh5rh~7rSF?M~aQ?L!p7zt5 z^o5}RS@|W={>umOFrF~C{$wrL-gq&<$a9N<>tzQE%VkYxBa9@=i_-L-O{!DNFm;W# zOi#z$h^L+m^ka-po-emHO0u{4U_`xj32jH6cbLXrN%9C+IKixec4{L`#B#LeBS7j~ zeyjd3&DNMq`WAmcPNtAvxv~zn#L-nUv+3>?jEDY& zEZ6=~do6(YF+QJ7aJI#Fm+&mC+*g4UDif6znfb8a(2o(e<7mL&br8Tmef(Yc#}EI% ze{F5My{r<+$MkOsUX}IIKF5B}3YJ0d0-lz)6TMVEUu^ z&b#_}yOAK_wAH;8&Z+zOx}n72v^jZo7RCaj&NZv~@M0*rVc71$<4xtfsTTFwL1Z@icDCUND$QJfj1**{d4rDV|ODi10tDITaS100- z4=3=PKbSsUPmLlACVI5Qm2$)!bO?U$PqS=W5^BdWY&Lm)U^uX@591G$9cWuSuAD;H z_7(WU5OOHr$bxMxZs`74$`)h3&Q{E$7$J(~E56<~A=9a3aqDw8;L%>eAu+q0GO>pq zAy1in^+e<4c}Jbc*m%=6G}x^?I}pCo@NW0>(RA$Gj%s9+kfyDKBkpLsuPA-bAemr{ z)pD)VhRn-yfJ*Ffgs*6@icHt+>Lb#4mTs`Y4O1DWa@V?^dxYf2Y}wa`cO4fdK^xO2 zA9{he5}$P;_Ofc~EOEy`aS86dnDB;Xch)phSApLPH$)^w?h9oiiyYK8tPP?iA}04b zed;*A))_+`b=-3CWoLoVNV+^Wql-dFZNtyDe5TZN!NO~u}wbLp=L_XuE|yz628cNz33cjWBG_=1@wK@ZD`!| z+v@j0@kDw)KU?a~44m1$6*$$_W-owX!6m72S&PTas^Y2k{&|cajBt)kpQ=u07pH0b zh6B$F#>)ljTagjBLP+d}v-H^^jna`|Bh3@TD)YPcdn+(YJhLJ1mefhh4ZV6&w5Ug9 ztKsL3_Yvvr2m}icnnfI&gDWUPcf@{~lJ9v-Ks`azw+rk6iz&o_k?Pza)`ex{%rRH5 zW>)2fx~0wr)V84l7XL^sClhA|?_n2?e3>iK<<}1B)~3!JVZ6O1Aybmw+;y80xJjtt zeBKk>h=}*r-X1J_TC}01KhLh+N{umesXA_y$Zg*reCCwOX&KCr>shsXXC%0G%`-qF zPLC5QXoC!eP&I@R0DToQRQYSlNyF5K`J7rW*2ry5XK%%Y4d+bQN%$)^Lr_!QkrXy1 zGe0N1Ug;fOCvTogmO7K&b2;RU191AY_HU?4^VMB>J1NI+6Sl-|+Ac+fdXl%^mU8hn zmimW;1}q}APuv*B;Jr1AqqI})#62k}Fqu1am(SihDt0lGjy94RTLmnrwdM6R3)O|+ zPAA=x(p3+5zt&>Cp#A|KQD}iQH2YC`g+%cMn)u8#pY9iMv z`}^F5#OL}2wS2sQ1%96J`#$b|)=qLIzIJx)X?~IcZ=`u>9(fprIq6yak-!_ydebYL zcO=m|1h=5emz1-L@j8}mi`RA82Ufua2*$=Lvd8x2+m2C{x|@~O^QWl?d|)c!N7Ibw zonTnX!=td;kDYsRm2`9Cp8vt#dxyi>b&JF45;Y-82oi$mo#=@nB7z6edmjYR>yU>a z2$G0ik|Bs5%;+;hlpw?C45J34jNV82Zc?7S=RMas*LR)Y_s8%0PLeA#v+uRmUTv?v z_S*Zt?>-u~@RErD&kd^D=XD8){=&Cfs#SiktX`(ng!xzvTtr-pob!GnwCK{m9pefa zTTpo~w%+zUPiE9&=>y&t@@|~%bNaS%+l-qh1=m(#;0TrU(#0*?g2wDA&)`9Yvy3Bh zGuusmSJbV~07AK?tfP4c6l!*6E}77z->Q+Z*H_I>e(RJziYNcn#?I7It9{3^Mt(5u zoK(v9As@jqp4i0x)V7LXq&NR${!4MoAsT~uPa#$J+cgpb_g5%wT9kO5e_flj zbIBH@4||M!$)58*v2aDnXMA7fGi|40ZQN=~2bL@3HCnXzu=$o{*pk}A8A&p__o}*oeXXGNPcpe>l;q>+D^7)H@^rDC3t&FS z-@YjRU2fU>?h)Ujm6uR`J3T?hK8asueEDVCx9BUi1%Zk+GKyYXkF2rWt+HZY{5ib! zt?QI{x639Wj`I)&e!1;{c~9C!&oS%AU(X}_*oT|G5B8*sUtJ12V1i5I=N^2e?y9-C zg$n;@>#jE|%mIfo+Fq`GGO^oJ6l2g(b9bdQ3BnA2zWr=``uyVFN4DCt=lJ<2&bC)m zkk_|I4z6pccqfd#8=q!d-1*36#2A#I>u(9z=8|sc`1JHi+qIyCgmv=@0^da2<=WcN z;*+b>fLihgmo-!>S(q=Hm=N7O0{yjG4=FIoVu_R8UBXo z%Q=33lHyQE0>y>;_LLLc3+MQqkIuZ?p6hv8kJHBM!JO#!wZ@TsM$n3@i>zDkn$u11D(UC@+k_s=oJz{}q}|U6+8(b1 z+k4dq_PiYnIfCY5&maAD)SmFvft!vr!$6683EwBwQ< zz|^>%TT2jtr=B83190z+87UbjL4NL;i9QeToG#|YvlGO>vW@!BaK>bv@h3Ez0F+Yz z&EFsY{sp-H8=^Mk0cQyRGk$<_9g4QFw_o$(j<6R8A+lz}X@X5=N)mFd&|oN;Y= zxd5|o?KI0^` zx}|)GHVF8bAEZ`+h2_}CYJzB65*P{Hu%m*g_0C~`J9>i&h|;$+kL53TJczuBu)Eqa z;qlt3)AfPlkfNiUjxEUEDP_U#TiyZks^hyn3_)y@i6lJCeqh(CJQFdPsOMN|r`~6i zwZ|XLU$ey~h@XF|$NE7PPseTm$LQP(Ijtsa;Mb6H2HNRmlRnBFETO5 z3%~wVS~_MX4Mxw5J=k}5YG!_|+(8JOZ#YI}il>$b;2Z6EW~M&s#Y) zEmbWE_jA9!)rsD8auSt{mQm`{o%lpNJ%p3WWmmxk8|BN z?X7lX**8-|vn@B!zr*8BOKXQl7YrwgA&MpVqRI2#Ew7)cw*iMGe!#jE9 zRbQdf)kNm9BkLYi*6akI>ht0QX8P(NU_H8IVPHQF&@nV+uhT;=sh9;UwjnELiTH3T zOyE+D3a~*cgjuq-JHakj0yz@TKes_7Rk%l~7uZ@fuQIaqybELqAu=UDAWsVz!j9Eh z@o!pdav?_&`CB)L@^v7bwi*j)1$oeJ1tDWPAi>&n#J7Mz$uHXNp6Zt#ra0Z7lCEg3 zmg_7h`J8`wMrBUTCA}%a!23wAz@Nw@dT9-o%H>n!EF02ZhK4vA_$wp%GAbr-i1IUxW_J(##+8EySi#)nyO#aQ_8=@JEv`` zb~uN$bMjKmqFmt57ssbeF9;VHUpL*FRuS_-GCJn#-8p*WM}+Cn+|~fry+gD)2`_+d z`>f=Bn-W}+5x7?`k(JzAzU!(4|2Y-o8o(Lb65OjZIZF#I>Jtoh$zRTm>*Pgl@Y@dG zriIvr0Y!s&2PDjryDODL>zWP73i8zJdD7G%q@omXAtY&5k$1wjjK_romes>b*2)wkgAK(+^^V>PrWoD^tX<&)4y-jXwwNoKx5MWM zYF?)T0i!kvS&`C+~r`@Ji>l~z2`X@-LNraB)QCziY zO)iZ0gHsDvi1c^>bo0Q#i>Q3Q+|6(+E7x!|{ca?ArjZIVv3tE}XMzmt#jb?+|2X_Q zbD=dX!5O3DsFQaD@T6|KLs{ih-@lPg=>5X|S5Uv{9|Zw>^c=>PB`xJ;oXI0;E{{gqN^a8(d1{SqA>PO8@ckr( zsMG{X;ViYCGuz))dNMZ{(zF8BfXdcA1x zf!t`LUGC1A3Vh@o&7NSQ)UKiXT-AeuJ^g37^!frN{J89#uRy}UV>|o}`&z5-U;ySH z7p+h5nUy~$?t8f{#rqW_9rAM_fyKa0HrbrcmqF&`R|W4($L%ZB76DJvaoJNOBbEG~ zo{QsZ;dAEI+zU;)i~G7m{#*`9E_Q;R4@Vn810d`g={4kd`-_XF4=aq{g|Vsh=zqWp zp>{kSb@bj;7d5(O$*n$JKTUcJZ4El_?VB1MX67(+p4A>@tc)5vOl27p5CMXKvKfRuY-Q z;4D|`u47EVq;3X}UT9_!rL`W!k2VG;N_;-ny8OCjm=l+Tm&Y9Ftt1n6gfMnNR7P5}kQ_guK?jjJgbAG9TwuG@6 zd=mqwZhTJQ7=lz%oy{pCtgv^C06bU&iOx5N&O<9uzwfR1ZCm?BXk$FXSXT`Hj*w{P+d>I(xgj~jbR4uwc(-Q z)sO7R&%C>nJjj%3AM6Gjp5~MNBdKWp8W_yj%nl`)lIkPS^>l%#`PjA?i5XEobW9iG zj@h-S;pmu$-P_85U8F>6rsu4H^zh#If{_?0cI^=|sOD}tUz9!7} z+qM8b8+9z1w2{P)Y}wEO87k+1QDCvNj4$BJNtda=zy_vUo%~%%O;@a&=j@3dZxj*{ zehly5gY)N?hJ-%{|F6LcjQ8Jw$D{c7;QjsO=k=4{{{s3O^?wK|wK=`pK3lgF4>+dS z3Vy*Wt5+Rq4TwseUbnyV!2nRfiuLOv%eh^mF(Kr*%EjT5+k3~!I$P>VB5oS=P4YND z_g|e_I8M1&tkphR0zc~$E|Hw1=E#dWKLD=jEuR21eJcC`fM+DBWq21b*=_>a-HY4` z=iga7gY+Mjy{;vfK91R6J#Ff_sPZKYg(Y2WuXzR}nE+}x%sE*PuzbY@*k0Y{zjhrS6crH_AeBEll~3!C+dF=`j1$D!XEQ`%Kz{7 zwE-`0B4k(hQt&(C(Z6$!Ust6Jzt#1hZq@#IyT*UBRr})vxrePi8DtNJF}PS`QWt~;A!?qC#oUKAn1KOM=6W>nzwG}A;p-kLuhrFc#OYIaaU)hZ1@fV4CKs;h=w+Zwd0SNI zXwA_|~x2;aE9~L=~K@{-E^7u{z}~av_GiT`4Ttmed?4Ms$dYU zG?#D%!a#BAR6+74{a)gZwZd34Ak2cz1rUc2*I`tJqPYQrx9zzH3ydpgatx9kAq?Gw zjm5PtrU`IGXlc-dgZlIh4xcXVy&<63W2zrl3S1DUQ@h!@rd6(lz*HT+Dyyzz%NJUg zV=CojnromV>;PS#S~8~rNvQw2|`lP%J_pF;@I8fSiRfXL? z6@R&FUth3o@KS9;=;#$aPeGD9niAGRJ}q-?hn9uIDP%wAPj7Pjf5q`BOLW$IIp+U&=*c*g}VxS)4X)zdvoT7)l zu&>GITr|9wHdDbQSjP&DLeXRk@BtY-wIe^FWh*O>YGG3x_3TM#xrg~RDZr(kT}x_3 zClwluO7hKJ*LA#{P*{^`blc#CZC>`%n|>)-&km& zS8+!*G_y#$kT*5nww|=w+Uwqje6ha%I$bg>+3d%B*zP^L0Iabf3{KKMC!Si8yB^aXJHrjt;%Q2Bt>owWD=OW%?BZ7mwZC#)=6PGs53Z zR;X=f<;NETA%Pq?K7L|cAPxv7xTS>%bE0Y1CH;e~9(|{E$D0_bu5zxzC;4B@)dtibrPjT+O<&Dqjo#P0Cp;>FN%&)-@YLlYiUBo#jVkal5M+beCm962N4zEKHf zt$`9*wg96`fVGUlpfH_EqmZYVq5AGyhu-hf1-L3G;pbI1hHCWV-Vu>>8yt##nePG0 z30F_!Z+!dPST^Ibx!#k1^i~G#%(dxTR{$lr=1Znx(Ne>L<%KRV|L;888dB}Ne9|vH ze~NAc@|w*Muih)VR$VAi1C12C70hM14UPI64<%Ril>$K-VuP*~;6ZGZ34ulVz^iQEq0fVirp|Z4!tM4bNLCdIM zf(L%LqqPZ(EsBm`+P7KfNS% z#=PQHwysYAfqaeB$NEmBMYdqJzp8i#J`Ux8GZs`P~noGjW$H zSye@&^q_KWJ8SOwtVK0FLbVOfS6EUw#znt~zojqRgKLA;%3A+Jd3DtK?DVU)$uu45 z#eamBTe(PHeH@ARPk}6fU<(A{DB$OD{5_7zKUit7x7l`RkJd~P>se<* z$=}8V9&A~>$|6l>);vr}*b51KxEoo_DBzx$dWes7ByJ0ANnjGFL$;0;Z!!e#vDd92 z0Ic;+!dPAM`)RqgLZWZZyZAnxw_{oR^#EBj+>Kq9I!J9V|32R|gQ?#qe~6+X^%3_? zk9FYMWlsOi*`|Q$&NbmNzmNN`*3K_8L2AD{ld;oD-W~n0zZ+C1Y-@UUdh-pM+B9o_ zd^pfWz}?%QiybyF%tUA(8u-hn{+2r->|4drq#16-yXuzvC0kR_G+Qj1P42^f$MzA% z3^(o#zyQr(zKg~JWbW{6&70xS-c7gMo1Ax(=6LRyh+Z;2SkpXYJ7>*HoTS&A`TLj%j}0Cl$OG$he-#Yp~!V+=76Gl{cyaff{?CvjMlp^u}| z9d7##v3O^@fHWc^OI~dG5$)>g@~$F)7-+J4#Bp=29>VH$1u0f`P4bPaDFUOM)ZC{6 z-K)21ktinv5q32wrm)qJOo&?ln9?_ zX0u|^cvdqtiV(T)X4G{`LK{_oS>jdJ#WW4#lnl)KnT90ebMjRW^ivqFzuCg+ z_P-F*Xe)?zPur;88ZF2yA+sqE*<8D`9mxSzk%a{8Hd+h#f2uQ-Ap%q(AbibtES+k> z@w9E9x{DWm^~YrTIWw)m{uxP^ytIyJa>slF^h_F;pEK?K*ufp=b?eiH!fjU!m04Z?Tua1?aF znhE4!hb!YOhQ!WjbCj;lW86C(Ll2viE0%NikZ^GH6E@fPYmtbkXq#lH%p--^=T76F z^e(=7-akPz(GH{veaWQ(KEP`?Bst@y+HE5-q`>&9>Le_hmfSKQ<}C8Wzej&*m=uyLP5@^!NUqMR z+`5FFs(CBtO`IQc3wB;C)FgJ7OeO%Tk2Nj-;OtyY0jWlzX?+3WaSq@&Xh`DZ0I4#V z1Ym}}>{@jzhM*Lcx2-A+Wx_i?5uqYOY~pytfu4>- zA7{ZE3MZPOU0%5|!421MmN+9RVa5gV`1PeQEzb5Ql`>D}oeO-TswuF_+I19;q8ngm z%giJ&uJIiKeG96TPV5)7us$F#T1MzPAQVZP=bc{eh5^YnsApabWnVgC9-8O^a z=Q=U9Ab#$={%R&s7@}ge>yhwAy)-NG7QnzxgL#SQTH29*6kvZ6p;)M}3_k;>3k`R# z9%DiWrqtN5&xm$=)7GKLh3jEO-o2vH7>q2CifxO@CfkL|l6#IN1l`)8tMeA(etv6% zZII4a#zqK+UZ!cueUhtgfv*WLzy zZ>rbQVgdOZbb`4hZaT3QO(bw0FZ72Ec{>d-UL*5^jkJ-1l5elBqdFUU(eO!sgW zAOcL>4zT*v)v^QU^oHsimmt@~LY*exroRUAn#U2EE|Xht*o zISZAMf0eExQ>EM!3Y@Mm1%~%s$~`VFvT^+Q8Xq(<+&iAHCoJ25wD5|tK~rc5KS!0a zyy?V%xXnH_K<$h(lQXGZsE%@z#C60c=(cOk1}F`M_B$xh8+o1d6SU_QDdYi)6;toJHg!W>8D~ck{>5V9*{uzQh@;m16*sFYKI@waoqn?RxJ;s& zto3UK2a>HM`+r}Qiw=MNJiSq!Q-Y`bLWH+XjU{~@1fm%V?Q8w;Wa6|87-vZt53OfA z?zDAG=H89; zl<{X)YH}7%^~yfxI3?qU#(EBSPJ@bLi*G@5CYIB0fS-PxESEc^U~aLdH;|I@zXK<# zt)Y@OHZSWhf1FQhe0%o;M2-82L!A;TUk5bI{atzaManA~5QY6QnK#S;nKi=z%k5sT zJC9vRkWQpg*Cf@X2GZ!`=0gZw_HocoMdjJX$|}4)-m5rLw3N>GLxZwhh=~{bOJgU) zsM%oXz}I5uHF0%wdS>L(C3%uCE~lxOcP*o;pygyYWm~v$EqAK#pvS^=>C=>aos80a zxPdiJHJkbHibqTT1s6_}KIli!Tte{m{2NwWy*57S9yOS3sH12)MW_jD-2sAX?gw3E z+%R)u*iq)S)T{X-+2xVzd5eR{5zi3OetS4{+qY8#fn#z&^Hor#KwG#{V+^9Sq;8?m z<@B9IpyF4>-*ueFsTj!9L6mzs0X|980;Fl8hV`?L4PBfZX0L^$blFEi`%-)kOpLsq zI6g%uROH_Eqh&WoWY%yNSjh)ti}N{)-7x1i2BJL;$uui$x7 z$ZfAz`J%QZNY!C36vh1sZ+J7h?K4VjyQn`K{E8`4T z-PA90J&+$;N6WT%j*@XDT-eNBQLCec6sh~*FC=6Y_8EX?)AUlNVetBX-1Z%jxjteB zJaK;_RGf~!`Q{}EcL1R8^U63s@7OhLh2XW&Q9Igf*ukQtc`9j#fqp(bRHt>;a{cC9 zZ@?5(xmah=4D5aJ4Z31#I{k*o7%=Nd?JSH1_IiLg9Osm`26aRH%1Yn{wm6-5d_V>K zp4EmQUGj!}NbqHR)NIr)H1otH*KR?VKex-=`|H(nWUT3-afH)4nkd&tpxUXs%RUWC zfvPWqNklNB9B_y(Q*9f1jLy`q8LscZ_|0=9BlGq-bHDPTw04c#t9d1~Ck9DeZ%K6jB zFfk|-_C7K*^fWknGyCePn%=gxPazB@K?=sc?kKC}nWfIjVn}5)kF^BEy1mm(BUB=) zsf}A}N~8$psv$vE+R)2(Nne~EblngH(@O?CKsT;i`mZg1N@QX%w))sNTVlE?eet@3 zC>EWST2}N1ey`x22DesUEEioQUP0VF`ykEG{#cnT59H-O2m1xdQ00^$_D_RsRp=!X zTwnD|-HOkY3WZKRmK6d|?%q4xiMu6W0b-<)dRyG=_Qay>N*2}N zS=)NSTh49{Qf`ig@BRD+;F^A$VbxxKC&A#XGA?X~bNZ|-TCM&qL)~jfo$9Zmpd1zY zYQ2;X2-Pp3s%N7S^IoIG<0>gD&7mtv6_vNMeTf=n2{nwrE z@!ri(l%Q*+?9y4H9?F{w<-_Lj*A^ZSBXCyXUJmCGPlw@c$r)Yr>Od$t|HdHUzE$%|E z-{hp3Nrv=`50Wg#+mvMeXAtxx{rr1y7HxfAzthO0-hTGr{Q2(*3NszIX-s*AC=x;!E1_qBMCJ@F|#Pwgzfqso$n@)A_hVHwKqH_{V;=XPGX z7Yx-stz4tO<9=i*qFU=8ai_p9wE7)`y&YhJU7t=4|-T}jBf%tz--{R);6W-+&QfQ%20wP?^8W$ltq z0Q*Wa!|8M8s3vS!6DgG~c4mzY#JsUtYyf>|Sm6PslW0#fl|D0yNWqC~^tSB^xLlk*5|8$< zjf(e*KcaQ7TOO_51bng0d3PvNrAvUH&i6dPSCr{mhfIA(W0-5r&Yj!L7JLd`VlwH) z^n3nYXj?2AbGO?7N)`G(T*5xE7(b}WwMk&gy56cu)k(6_Y+mxL9(@SvcDlcWxSOmJ zJoTXJbqbcAHa=QM#zb^uCIc#74HdP!4~OQEnh%#>b;PTLs`&U*C_1X0~I{jdU zkrXd?3qSL{Y~Np9_)B9=8KTw}*LdeUwH(lQm}qFaz;m~RTv=FMJsT*$#wdrN9syxV zx1H$`-wnyRe47sA2WX@%%`d1rJofb(63TiI#N6`@Fh z=NF(^sfJKz{_oJ~xla-wEUAmu);o+z>84}e26_{l2SFiWAF$s>y#9uv#JSt?ywf!I zH!EY@^L4F{(*(XczY3`O%#mP*jYy_#RXfPF#ZRj%@N05MCzj|&y_W!N76=FpR0vD; zPr|E3QeP2OooM^blo$3T_Tn%&;4sUg?#@*2JNQj&D2&r2Ygnld>Z2E_c3!P$h^i!1t%?gU@ZU;z=twj3u-QR#;p|$>eG`sc1{#M zhCP%o!=$|P(j@vj2zn5DYlEtC_Drsg#gy0z8_2f#{!=%P-Bf#2VMXD6d!v8>Coti% zFTzg6e6uEPVF{LYX4tKgn;J-$CH(ik=@=%Ofs1cmIv`z=;K@$WtMm1rmUXw~rH z=PwBCn(v1bCdw(y-Ct&XYKN}}-0CbiK(>^4Y~8s91vUUytU%{L1X5+(?9-O>n%KsY z>}-|L=qQl2Mxm1B%@kZ{N44y+CLP3Kkc;#=>DFGTWvV2O$tRuW;_(Gc!M8TncT^;K z0A+Lnx+M29x*__gc0uz~0;#bRwK(zcLq{^ivZQ@#)$)>kRPUgX|A{;=O;zYqhKO>j zu&$ut9S8|RX_kRW3SdHG-}#VV{id`4tOX!PQ(<~T^xKE6AYm1scipb?5|2`=BQ@;G z&JB>Lh^D*tP3c8lAk?simQz5jr9M6F-nS=|R)3U~iEtF!hfrYM63-~(Y}Y!TTw$TZ zm;zH=ObY+2WcJYt-6%f#>PP!xw?X8@6*>J$`dT6eU%KtKmtH{eAh3X18oUmS$dgUB zt>q0x@*eBDYQ*gnr9TnKk3<>AvF5UH6yOVNqsWOA6tPvUfnmNXUI znBnPto&VsvShD?;t9eR9rBO(^M|&mHv?&7DBV>F;_5(XWB>3 z*Kx%qg}~iq@ly;0y0wby^>^COsAuFx&R`ywgkRflS9_8@2G1Y&Q?&cps0@& z4|Ri2R?KTF0az&sw1=v z)xVe2zvaXMb<KU3mO|$%2HN9T_(E!`_runHNK+k|f4ZbTR>CS9G zf~nQo95jQOxLRIL%9rY*!(3X9rS0@MJ0nc=n=eso#n6sq#R717e9gC&yAd^A{fx5@ z(qK9yBho!I-$FnnL+QN@{dc|ql*Ejes|1OGs;S)ZIN5HEoTdMhR88y%!+IkOOasp` z@YSzr6Rr5P(4)^6IlNmr#6OgsZs?gs9f+iBo zO9l~}hC6pW$Y<5}@o=mT7`|fw`A90&Uw!cY@mL@YKD<=te4TAf+Tk`I5;g^Kp-FWBBU z19Q}>n@A4`{0bfQ7FT#BH;upEV$Kp-7N52AD)Z5m+%jM?ka}%X`z~=hMgN#>*r(zl zTcUr{oxi|FNY9`>hs3-n4~2PTEo|JyZIfp^DimOtOb5il$HW5+=(@x|m34-nR3;!( z-`I>vbu7Eje!C5V>j4m+2#^&(&*qqb0tvtybYK_$2>>6UDbg^_cjcghgAX0*IcEp@ zzI#w)7IO1_hZY{=VRE*(-h`18TjRz|of9*FIQ%od~hk z_PqyK)yB5Sc(ZIo2P7w!7z%|}q)wBE%MA#3vj5Ymp2939X-==MG}TKk^`XAa7Ji~q znJxxiq_GW^%BA1_(KQ(e#4!>UV0Y3d5bO1LGCKFFzy~6_Uh4XfN%}$dObvO%N{%vq z3-OP2r;4n*@?za|39su%rHaQ<5Tg=ztFe0il$)~L*e!K{WZ z*bxg&z+2}pXdH8^I$R?W4GN4q;1PhmJFy{E*WV>Z3bwu`Vwy8N@gGYh`LVoFUXFd$ zi$)JOdD<-dT2u-})fDH%_)WggAFu=W-r#_JtgUp0^DXsTgjirYYdH2LRRyAE*DJgm z?M*HiWB$SzpqL8M5A)32Lu>b>g6#_3UchuT%3d*wZ&(J~`E^DG6=t^U&|$QGOU{=; z;mhJn^^SgkEl%F;0PpEg6>E|0e2u~&CAF+vznj>91WiGnJtrehY?K8RgyjI-n{9?3 z-cty!54w_;I1sayb>9o#-0^zVNyk*Y$he03Ag*-C_byLw^&RS})m1`QiHukx3XPr# zU$X@=#pl2X&KHNhHAMzq?s~7-Xu*u|ic8x3`&*YIm=w04*5ZQ0$5(C*s)+# z6?k?gl>H%{C+siamq-lDGI~7GON!25J+oym?c+Lr27vHS_OL;MV?RnE4DdOGU!~pja z_J~RASjL^uE$|5^7t`={^vbDcMMoW6pXBjh|N zoNBVP;Jyfp2$;NGdIx-B{V z(a+r~cBJ?-K)#eOyx}r`=Fqn(vk@JzD*Lo!N6Y)jU;AOE;~4uz$J*89{3vGnP46lG zVD&>D=QkVtERs)w)T;o6Zn4VHDb`IL>7%Tj@!#4yK(th9je0H*00(du4)T4Ea^7Y- z9=#Mltkad-fojBvANCx5H{1a3T`E?rGyKuH7lY($jaBDbUgDm4M-BD@DyX&u@B%tv z?bJ(!IR{0l!k!HuZ>uTl-y+wxwcGttwV<*jo+3SObG?fpy(_mcL*ny2vh^co3~_;+ z0SDlq;~r~h(?A|sontpxA#IpE4a%91FO{DYUG9j@axqkNn$*%78MTehJPa4s7F16u zow6zWeR_x#yWp-@BKP@T)D;kgQoBD5aj`iri?&k%)^lR5v!U@()1{Lwv0`i=X3HPW zV&%KET?#sxYO*IyxOr%2R87Omiy^!6dWv>)Fx@VpyJewRbbNH$XTXVQD=F~xlSwZ; z>5sk0yAd6tt=<&mmFdp`l!h0i7vd}W^0Yrv=eOZI{X%|zgFh!(J(z;|9E(_ zquOJE8e}Mm*M^ZkjeznpO8pItroS05u}#8P@FFbU7tB{*Kt1aJI6CC-aeQ>BfGd5z z!LiKQNu=5atdfI>h(E0+2+OiOR@MzOkRQyOJtOV@u{$vdx!dH&S8y6>vpGjhWqWXA zqq=m9AP)(Gj+qOgOzvFGYt8smIoBkOzxy3~>c`M6ht)?4Qc=gADs2T`z~+}Z;XZP! zJCNi|>k9-s4H;jan{lQ$7KUZ@Xn@{1|L#@+M5y?uTS0d*nplpx z*H|<=aBgevBUHQs*w87VIv!W4P=t{*RhJs;@wkeiGkAGE9CmVyNL~B)F`^S0*MFnD zg(8f9qfn$xi;dA_AY7m1cej;GlCrC_YO2A$Z(0FrWqf@754BFv?M1dk+OlBmj$O!t z546mBaI{{|_1csEiLSBA=2gttH*wb^$c3)f27x{cO0AQg)c_>kQ!I= zMbz9#GCMwcwB&%Y24`wzW_UcKC55~~{MD)CoFGF4#F2tgv_r%dU@1T+DPkkIA<_57lWC{&x4q!Z}c_|ZkFa8dte`fuPTsd0?Qjq8c<7hXLKwXRwuCs z?Wl^#fIPF&ZQcQ%<3!QfEJO7>Vfz6)Tiy9)E_8I%7T2DF8ty<3O`lFSPJ?lq+M{?| zBt6gkxqcBGrmx;L=ip%2GrHOoe0&aTs-$LeWb@) z*thEQ-OUGe(vqbSYizPayaDU2MnL;+tL5U{%(a{wy!3nO zzpD_|{KU4(uso+dw7;0Ged_oSlXK~e+qcix-R&PAcg)o@{~|lO(319K2L81G6UK&( z!fA$c2gIr06cY7Te`KJNx?*1We;~3AyGbg;VND2U}Nx-Tpl}1_F zEPS00hx1^i)SE$`90d?#VRr;cS`rDy92jEdr?+Y(<2_hhM%`&DJoo*7O}T(Jk57Y| z{F=Wn{J&mza-0aQ;BI!Z-aMI6>5^ZNlb$Ryf2SAs6v8fqZvC+053c`68vgI=6uCw? zK<>2sllNS>f?pN~_RkL17iK(x<^DhVJvgv=7!Zh9?L7780v=X3_UMb_@qG7({tg3# zC3_OO|0BBZBcq3w|73Z=FSfQ*N(9U~qkiNVKeUY*b8hZ{XNml&WN=_zk_#Vimf$~W z-aQ2Z0cB+6{%^=LT>bx!%t`t$+*FEY$Q{&)KMhKKS@pIV{mqu2ay%yN9Mary`8A_BqcckKgE zMwQE|QQ2E)q_!J^vY#!*$gbPmuHeB`_8rOMz5fLA6*MM9K3~@s9z+wOW(ik7ev;sg zs8F}Z`_tqp!wouy1H^o)&YK*;92t?C|6)idBk2JiE8Iuy$5A-RSa*GxifXd)3aGcz zNO&XLzIqKFJg%$6Ji2p8c{n7v%X<-($Gh1ofqr1w8ZMF|Sw}sa;4jyfGVXr|v zL7{Cmzz4k^xWzGAaISVTTg)E(Xl5#wb5?gmkQbX{a*@ev$bp8ol zqs>Q!fXdlOA&WG~%uqhJzTh4cjkyUCXA)A7tsi2kIwnH!c)5F`@33ad&`}3l8Zj}ogPhyqJiUYrp=+J`$Scz(71JLE z19ILLjeTwFCm{YYW>|AWD3eq>BDY9w&MU1Ag!`LKr^gLOLdF`G(BuE zDg$z^PU-#*ouK~}u4yDW`|Y*qnDB24$RijxJ<5DOEb8&UB7{auf}ADV$r9?(Kf-*; zbEq4tyyR`};r;b5xguWu_{S8aX}!G7{pd^E&^-bf`2*ZZ^EAZ@0MCpIW@Qx28{j`B9y6 z)*~Zdtcbf2PPVY3iDHIx75=9tBIzW1v>IPmOKO8f`Ie`ol-X4NNSFZo5ZO}v+8j)~W7sgmE~lbZQI&ZWsloQWC9?G-s^2bR4fYt6^wAl!m~Lql`(~^5OWsuq=`;L)kOsSurqaSca_pa>n=JHjbGG>Hep1!(diB?6%BJ7LFF5Nr zyh}P>+5Osdv5bI5Hm!>feFhFX0nOu?P&xU7v#c4$&!C{GJm_$f8(GY^jW)Bpp9N=NXm!p}QbL}I9jFoxmwV+Sh#RK_ zJzZz4%KD9C@8lMsc7;x-OG|URvuzjL&6k(k*Vcndq@PW*sYVamQgjjHU_ZX!gIs3rM#V4Zrv;L*+g3pv8=>gt4V6~aMIoCRz0}t>ob)4>R7s&fS zw`HZdML4u@B43sRZ)eEYsbz(vLykeS(RQJM>MifW(xTP-SxtxeXP5Lts^yv2jyre+ z?b+XsvzVH0;+DICsTP8+W$5Ws=g4Ec(BUeM}jo;0sX`mfkJiUXST+(2$3c^h$%6_oH6E zGjdGdc`9{KSC_Op;kyPeRPImV;{!77gKb`mc z1SrK0&l`ESGXN)#j(T?q`6MAGF95?Cji;jm?q$onNds3FkLK{cS!k7~oy0HON6N5) zo7!Nt<9>%sR~OTFPUzDm)YuMhM#--?0ZN&8Z@P)oz=WOHt`aAcvcty{GUH90W^-qQ zR#y5aOLVk#wo|iXAzA3_>HuT>yG_GU6lE-lS@ihNxafv*54<#L6nWuj#OC`oDnGr_l33#9U$td~l@9ETkfg{N+yMB;-CU59Y7x|OcRZPYgy`L!W(KL+B z89le%)tB^7hm_+4XwvRO{aibVZ^IPBN^l~?*jPWEyHH-qmx?(Wxb%^-GsKQv=KtHp z|0?SLBagz#2fov&?=A&AlGykzlmx<`PK=7=bRY05XWDJ+U(!!2L})+4m@a++AP!a0 zR75KnPIq${=Lxi*?FJ|59UN?c-ZP*yDnr*IQQ7^FRVQTtiJ`vH|=z}tv=_&khSMeqt!OJf1y z@mI~4fs1MZg_8FU3@)$MvJnDTzBDTgnq>@R+kogWN%NQ+Iu|uAXe|p|Vfxa@E>1#z zMG)EFxR-SUF39lcd6Q>#h?$ z)@G$1Wn)Gbu|+ihogQhQY46Q;`+gk{^hWWK9RQ5Lt=x)8W7rNQ^ftbqio5y7ZId!W{v2I)%hFDzLz;+?OY4}mE z3h=I_(f|@er_x@fl)f)j;Dm3)n-Ah5uCX_;Q)NQuXjQ|6@(k0Nb8q+D4=M<^59qnn zz9-jkSCz|sR`m2lx4)r*DvZYIuWc1Y?Ayo@kxn}cLyPXlg2=^Q&&O5=G-4xG5b>&l z(2OjdQm|ixs*bcjWBHhv_8Vj7G^o?1P!l-bC$OeqE(h~AA2_Mi%emh}Pe zI1#m{=HpAgnn^veGIXbSm9rud%s+C&K^RuM)y}64Fx4NEC@m|p35N_5Q& z?DlDq6MA;NtPKi!0vb8=DUZxx|@E|?nEJx?g1vVghiWM>WVy ztP|sU196H<{}uGs!jVL{EDRS1XMU!rmYh3DeW&_OcNo}@F~{S_^MGTcQU&i)FWL+? zjCnLjpMjx-t#6Gw8kxDS$?wa~z;$5<`ZS7kD1HB= z2C6qe?58g3jJY8pZ&Oq*Xn@t4eUwA)Q10CSu>_*haLLp#P&^|pdG!eC_hNR~n#*)6 z0pIp)f750hU7*%6B)4X&0#kN<6U$=F?l;A`I5R9u)cBeLuIrp^&PtoIUntpR8+}z> zG&>b`z?4Z)wCOjvZGux<*7@C?WOPG69GorRb!1Rq&ziWqWx9}=SYIF`q@|@P--x1C z;XiAfJ24G&Q_d~PEofY;9OFGT6ZpNva|S)5JZT5_u*`Jq>TCU9lkNZbe`P#|ue*oO z`yAgD@eo&ubG1|bdkTK87U4(9d&iqozw5;IFpT@XlOs30wQ=FalWo8n9Y1#qJ0J4t z;SbxJX3XLHlasdVdttAKdvo>&N}raK@vi2z-0Rb`RomOm5Vy60kSj9n#ay4x+3uzj_6J($Pd|ssSU** zDo9f!F4k+P5TBDt%I+s8H_2`00$K;VZfySJ{Ql+1}9;X%2mN$IOTG`UHJNbJ;5OU=Nq1Ot#Yy$C&Bk?_@b#5Udff_HLahIcUIbvM9$-UPw4m_rOSqdhXT4GOU%l3)F3=qsW7Udd3?!vWB7#(yd{#-Y!Cp|s?w!oC+% zWKH|7pR@c4HItsyIVnj7(S_Xmev9P`f3G%rR6>L8n>JQ2~N6EfiC;o6!&>x8a*g(pOE{JM*^G1%S6$h9f$Y~j5atF?*843 z^^{5Lw|7sHL@Y;8{0e)jx@D8b)XcfK$&EI53HS_mnPvb-5_|g|&tJE5e>9HE$Rwg5 zc^Y*_dDpA2$8^o4EuEHgapr?$&O?Uazrir_!+m=Mc(1yHj{`8Co5|S>_ezqcuq1Yt$3^E%lfkoZ;YC7 zyG#w4NN6s$A13(;V?~evJV}HMcpVdh3VmGnL4)cRS#1$LMgb-`-i(Q7)>=WS=~XSa zWl%kc-}n>=>Z~ldf>)Czysd8w97aVfl3jqZY~WJ}L3a3XDZDSQsUdzsK&bt4cFWEa z|8C|GFzry^nnNSyI^6yxdntUo-%Og3M6=}mk92b8M{Wj}hauqCgeY^?)ZM4to1f(~ zR2dKqRsZ(b^A(mOZEnVtM|{bgRD5b&Jvq}|g`?h|VzQFhYWh^y`;s={&8`%jlZx!I z5S6wu3pZBra=({y@l>&tz9T6pX-hhgO2-=@;S>{#TQ0(9-!D^@J zlA;{&u@JiFtcgkq?25HbByZ#yl2}NI!3g4I2<0j6NM=YYnWPt5Dg2*b+~?^7(It@b z)VUIy$R&vKwD#VRisJxDa%~@~<Ch4SbH)LvByY}ag`Fdp~@gjk3Uw9Eq3U|DE4C$jxa zX%B$9SkD4AZn4l4f7u=7gbOOZK^GTxA|-)+6&SyAa+?or0gCorgAOZF$%Q*VCUdw7 zKT3NL-{^eEKD13pRQ8_FrD z0hx~HmD?+Gi^>7^Qz#>do#X3Mhlu*7#yt(js`=w99D_wj`za-zWMoeCWn0~XFIGEQn^NyYGdVvHdvq1Eg5h|mP!yY6C zgotn~K`ur@!AZyxD# zK(CKDdXJAVOa6L>%sS=}NH5drP55WmzUggbsAWf=){ZfrA7U+qVx-dFpPuh_=emZ0 z?c{Lw^=C3aL#w=EtilL}R$#}Eqr&iP-CdG7qA=8`h5&H2{vV^Pb65$UZP7~EL3tKE zQKkNb@GQa+^|VBU`s@h@pEdd)Ev4Xje=?|1C!MY$ZVx;*Y0^}(Ivz{7! z%2z9idl`cd)rVn`(-*DC*r1wTXZV5IaBV#)$=Mh0`|EX*<~Y3)S^0K65gt(AW9EGy zBXn7IJ~v^FEX=K>LkK}3`=!4}3@u@lG_zs)gN(dqIz_$x^*1)t0C3W^JhjwA1+C>- zmE}D-o{1xH9vokW)iyBCkJ7pjZp|#qitYJR*@H$WNUl)s<$gnwo`K<{s+h=_MvP2- z<>4pqS?Y?awAbl~iwrfoRYJII?2NXVZb`__)d^;Cb$Ugf`$Kzsq=2Qhb=PTYP3Ru1 zNp3VaN*9TGQE5hC9CmS1P>WW<{uWmm8;I`GAvr=(0<3* zPYAPa3Zi#)2X7l`54x|agMnaq3w97QBT0t*t_Pa|8*z~(AR(Fkpv6jja4T;J5CwK+ zXB?OuRxbV-s2o@99gT5l{}0fMP-Y?=xQIJz_e$&N`$S0UMHpL( zVSB4zUNEkkbCissN3`bkf+~{pCT_YJPi3jax}r5%j{6HAsU9R+9p|TQrbJlVcXy2+ zNDQ)cix=GowXU!uKsQC;sZO*#pQ1uSp_tUIMj7jHU`mp6j17*1vT+x^HOIHMbZu4P zSw(KSn)FU;`gd)%gwPYj<8@F|Qq`L^+469s%y7o-xh~&>Qps0B|VfMvQ~fP zYUiL{`U$bVPEM(JTE;KwiLS!y#Llig)*rCPcGe|C{Wd6KwTk#16bMCbvk+s=s9bVF zTZ1k#T?Gqri$m{-R#W@z$9GAo4VTtU(_;sv*|DOWh^BWs^H!!GoPF$pEz#f~Cvj{) zBrGF6fU-TyjWLEb8Vqubqb*<$C^`QovA4=vmolC zc3MG;E*0!oe{G!)r#2oQIc>L4+iH5INRQtO;ZEAAZ!NHNqbSZS8uJ-dOcZ6!YI!P( zJe$+2OM!wXudxro)-G3R)uZOR5L+TyqG9?Gq??^)nT1%fNoYD=i`5> zt!IG(KrNs?3tRh>C`Bv1MC%XT+p}|I{0N#I>bY0blILgsXw+ikPU9*u7g{q8p*OGN z!E*=OcGiXyrQcHsIBbpG*uY65_q*MQK}4>HrL*6Z`=PIzk6J9K48}uvyXSf;$)L|# zeCOTnv%dGrmL^TxEQ}d!v}&SLAcKCgPtV9uM5qKjcA@rU9p+M~db_1jq+z|cJzfQ=Y3N$CrqI!nG?=oP%3?4O&xjxc(VrcUkYVZz7d%n zSv$;RhJr}AFI3-ou{%&o^%5GQW<)jDO}X>Cs3OjQApP6?f-=)>B+U&89j|~ zl-A$5u#8?<-`lziW@rxo)-_wJnLx!^4gkv}FaQ8BhgvfZfiSsPmi4`(#=Er^t1>jykI>Sc0&2Unjd4Zr%EogXdCZEaJUi)z0bMH= zNCDY*ZLNCZr@C}fK1|h32 zo?qoB>fm)$C4*$((nLh0=)0Jz9_mVD%iOeZ7+xR?tX7Mm;d|;c z(thf4o>b~<4C<7A(~VA@ijxNv`pCLKcq|53y)V`7KZ5mg0?bE#OFll-> zrY5Reb)?KSoqmK3o#`M6GS+SH*k!2<2O*ngP< ztUiq&4mNNDKys;3@$7jB@g;T_v`I3BlHSB$j$1Noa70vJ;m%q_%Div>6>|7_Jq)Zn zx@0xwgqZ7$Lq9Bbc?yW#(pdE8ej_`Su~eH2oqD#RQx7{c)}zFfs`vo{H16t?Q^P)o z-{*hO`+s=QV)l>m{eO%8|C4b4-!BF@^00G=`1;i+`ugWM+XnX5nRYSsv>{(-&dABg zf$+eEz|8O#{JmI=w+Q{)l)0eMSg`H~ks#>eLaQ)0D{cODMH&;Yovq=BcPcJ)snH<& zFCdI%@(hH#ZA~WJrXWqUF2n>^&rrBmqys{==LH}}=9qI>+j|6=@+md{rnx~^LA(^oEkn?3;_c`hTP?c=48K{HTNP}Loh=NMlCB7=W+DD)*0@( z4)Mq|kFEEGL}pk0y0!Y()a`n{0-z584ZIB5&QeS5|uk=KIpHZ;M;Vt)Esu3zt<9lv!Y>6OER0KbiVag zc(z|@$0#Sck>CELT+eN9e(Kljh=X@mh?a1T|g zSK>gg-(}@mAl_eGQmZ-xdOLPiKz$bI{U*tV5Jbz|Q0L>1QC^9uZ&* zagp5X;6_buX4GMkJ)?2{_y9Y&`0ARBje|IX=U%5z?P9=*jCV!+EBx_E_(?gLfZ$=s z9w~QdcU%Mrf$)Y7at7C=LP!=qFs-)-*#53WZVFm=WuoiQaZb|pl-DEQAK;X9oqvCSq0j)u9}viTQNSvG74q{G`EJ1BuOjOjf62Kq zr2c_M)bIMX^pQb5iP1^dZqz>4k)cq9$Nq_Wa`Re0>oM$De4oHj5?U93HpC0VnxO4ZRqO^PQqZA>g|i%%_Y59G!5}c*GiEegBQ#nh40?Xzs$Zu^ z@W-vLZ8?u;*a(5#W&gpE)JySve@QPE2|oi%=Io~QKZ>%S)dh!~Q;_}8reuTb!h z$$wVxe^&p0Blmw`8a3>{eCtGP13%s9al8cvvSz@yAk?s^Z;gv{WIWM5J)iiTGv>VV zPhTFH82|b28}w zWK4`L4F1bgc>@P%QBp=0mcNQBnmB@-9gIw#l`;NNrU-H}a55of04TfLnE>Ps%uM+B z&`fNNpFe^ACG)S3p`vb1;!4l5JUjq#B}P){Zq0uToioL8LU7?~fM-nQOJADcG0~KB8gEXrv%00Q<}E zMGOQ5zd7E$Dd*uw?!pwOqsyylxzr6a^W0sJm^r*Pu*}PZ*K`_FOKQroSd`#LLlNxV z{z$o|{MhQXabr(po{qm^#??`1;l2i=JiNnIy#qL6kM#Ai7ZW8Ilk}YAv+ZHk`M6`R zcg&8)OOopM?r8q4hZB}1noe>=fb#oXWT)D^lANqQG(9@e4<@vzOkKE6hN@_SZ*;Rv zUOETEm;2HtJ}p#fU@2;vn^k-%Z|hretDmn?;rt1oXnAJ~ugf`VemeN^2aA9039^iF zd3oj6z|x_)U^Lro72|C2-Cl+>&09b0*7ICae9tp8rSUp13Kf`ec147$$tuEczg9>N zB9%^~qG@uR85#(iC16w$lCyr2Vb3SfYucjrIdhjCitW8ESxaGG>0@lx13SJXE-*d& zW%02d9pb0egNHaZlR&alJ8v+1$LuWMJsc%K+_>EY&6l_Bg=iAz> zy6W4iB*+SXqfWpCR&dYaj9+CWd6j+j=1c@r0470%D1XxEm&k5UaM`9yy@gMHY)`)7 znEdBLrA|r#6gXxi^IzcyaY!nAh94cOMzQ7_FzMb@ah9~%79M|YI_d=*)7IITqz71? zjZ`B!t_zwfu&#&pCx6yVOt0nph#925z>>?n=@reLfB!Kf!iIeHUcRx)dpj_t`t7vH zuiDU{W5-K6#-^V`B0D0yJlNYK?2BQ+!FANNtDn{HDV-TZIMdU3_2w9Co7KiR?dEkG z1Mp18uRz*FHgl<{l{n)~#J-Hw?v>|D9$}ilIYQ!i1eSU%WRb7G2KU_UzjN-}L7gQQ z`$`)r6hz)lr!GKWyN#)SnZ{k`pu+r8ft9&5+pPnx4PV!Z&&Pu{$lEALsS~&P){rtbmmss$R z6^!t-hvc8I61&xb>odbsXvCG<^mUVbi~4Hb{)MW1oO6CuXu zt<~>kgQ_>9riL$+2T!yWKXT!?29L2l(oyp1kRIwvwL?KjPKRCspIobjL9^_f%0 zSF?*s74$GS@e?fkiwab$eiTytsi@CTHz zo+oDZG33J7{tVP^^mQ?ZNi>AAgC8V4PcJ_YnT@~LVw zypLg`}{T!j$yP-%osW%DQ(G^wY-B3ew|caa(CsTKpO?K-u&Gmv+#U^}dD)K%8$i zr_ISSaZxwbZhP%s$DVG;Qb9D&YI&BvjD`N-VqyRDDLGHRPbH0L1l>LLIuRel8i`y+ z_V}2AwdwxFSFJx3g-7wM;u5vqI#o>db+_R7wPHnR7~~?1Q1R&{!wW^&Uv&Q%ftdeu z_7$-(H8p_-4`{5=f>Ku;?F@`eNLd&FcFz&T+Qii9uR8||Gjk_^fuoa&gN36NDGMvW z+}+OH#FmtW9pGqf;Al?D$^kF}S%Yi=jwUu1f9^=xm;h!DCeTpgK+47n5CjMTgaIM| zQGggJI}<rFb0?aOaW#9bASaYBLh3Y3SbSe0oVdS06S7fMizhrz!BgCa0a*lTmfzX zcTz?sW`Lms)T?J_pefeBQhyxM`70WV+8Tk3Eo{yH9-vtMvx)xu0L8(=@t=pzKL=Ju zVLm=bC#cUhXej1OH7Tx6UnlDyhkYUFm%W$;NcT<@tSxxMYYnHsqV{q4h(H>>uYB8*(hYWtte{|-^3Ov2$ z*Vy?HA})m*v2P}o1R7#NZ+uc%y-N-EBGjr@R#svI%HH$9;zn4*^-C_*T|<$XhymD%Cl2nsAv4F1L&&s3`CFd3NtL0BAv zaHPUlQz+7Ma_`>JX)-YCXF!~1f#uw)u&%_rgfCP4oY_kKY%dRkEiLmU%$c)5zrRdu z{CfE?J{HU-AtiOlZQU_aGf`Xwhp0ArE_s+?sdSM^!}93?=u`iak$NJDAQ8--ul%`a zhe_pLMuuN$nIM``=65n1Ouo_=_obwao(Zh(i23VeoALzP^(bd{SN`+pi{s5>G$NvN z-L?-mmm3&EPdblUKMn&D@g!(xDn>@WFlIjp^M7zCHt)?5?!*ai#X42|rl&07bchY; z8H}h%z)U+a{+XNSL&y7l;QaeTziTN&{aS_;i272JM?TMUY-O(^C{TSGlKyT#<3`L;fdTvgYmuKqymSu6yw!P@`CcI}36rI0jgm=CZ2jSWmRsO689cM_b78`8ZTKbk3JuLi1cW> zE7?lP={yFo-nC{&`NY?vE!)@LE?z+j-I3|hCJm*E?Q{zADrop1DRs-=w5}YZ-NQA` zOmoD_v~!cW1}CD#d(6cH^7Hly;Cf1Komp`$0Q>N{Q6<+VukYTcltu5GCB3l1Bbp*V z6jDLu$ri=yvB)tA=j<6{xXAR8CTV9$Y3LQHt(mi4tGWLXmSebLm;m6B?60TGhklda zo4ZZ0#5ZJhI8>TDs?XdzzT9TWYhxL8 zRa#TTbg`*eRv2iiFni0?oBJt{+WY>4^O260xH{v~#!&~b0y#*txHe0;wsYi~%DhEc z)bEU1YTm~(psIYk?v2i4h0<7A$+BcEtE3Eu;yg}oZ96xaB{Q1O$h}#cVhAEt>lCkV zFy7La{Brx+F*t}Y?sVa9-sl<`4!>0HP{l-;0>ju(_(&cN=w7E!C6@S|EWanXZ#^v| zg2n6Cv;ticDihaA>xdS$YYS5?BT48G&)gH;9-i9eN_f?t6iGUL*4$X>tlY$2&iSYv zUSs0YP}B@`+sZeDg^hEwY~HBLyjGP*a~)Udr(vtZSTo4>++=R|u$Wn_3>gqx}>vC{t9=vc7w`8-tw| zbo(@cQl`H3s%)eoicOR5wa-x4rMg-@+7pt~^n;pZk#wtuUR-mN9&_Wz!#ju4E%R%F zwYK{(n!cvCgjfcRI9}{D%XFD97tY>_aV8)A0l+@?xiEUP$W#PR*fMwP&s$G7dTcV@2YmH=_a~rKsgBI&c7=^ zC)6B$MW+99_QOP`_1l+AW7-Ra+A;Uh&X!`$QMNflLjxR;%(&1k!5!^4krJMxf=;Dj zidkE->}pS|J>PX-3+WO}$Qn-Ld{d%w5bAEogQIGnDr4LErF$bZP-X4x^JF|P3++xI~O>@njERqA!yK~mv z=qcx7+%kFxEt*k)0QP=|<6fl+2X{ZdjBCm67&JS@7eHsTreZU0(sEqo8Rog(M(VNj z%QH167#AZX3JWPdk!Ml7cDr4v%!(0rl5GzZkA*76 zgW;8hrLehzk8eumNt@!-kU#h)6xmfNCctej`kF0c4XwP}RiO2dSNTUTmp}g{lP8X< zA}y}chbqQ06FKW(^^wPO0;_t(!{(+X0(-~9>G7wnEg^ZM0Qg_Zy#vYzYlBM5SmP^O zRtysLvIkmgw#5(m34TrX%tg)RKO+X18a)QiuPo~MI}U1p?WF+0t8?pZDzul0T^|>e z&!+t4t$qTJDTb_x(ajP-u#KD!Lz*n&J`eO)Fvdl`3Qt!JEPSQmmf=}_o$Ly(AZesI zip-t$y_@30;(mj>E|Tr-{q-2az93-r1#A9#n-l#3{UMewhgeU#!}jQ|PQ`uBAv-Nq zUbRInx=U5ibkqH|hXY#Nu>qj0O*mrL(rsY>{FO%_?4x6p_MK{O2zArO((u`JWP{2mGwyniyvlj-ql`mIc?sqQqI_jpo)LdGP!d30ZrjF)kDNLeA4A z3_++Z_IZk3EX{BC9}jL0$QhdUlYArh}k-_GAP<;vSjN zQq<;40AmxP$5~w{fmR%C*ext#(UX=%Vdf>d{Q9dsJ>Sg7HZDO0Y*3#R6nwgG8p2asazKKN zOI|5$op(?10fchX)Rz@OhU=vSyn0B=zBP&Ka!Dl!?-FA3uT(G*C#P!svOOcgs(fn>(d%1}xqvjoYo_qX*P}61G!FqAed$+K% ztG33P7~`@|kWTrB&)|saM(vx&7X=n0h2Ei$Bt7TlA1hS)sjd82RlZcZi#jJ&weLTL zJyybY)CjoCoHn6`>v%{go$nQq$)sAk4pwcNEGw7AY3a}+lDbjls@SXrJQ7tNrqb?} ziZCWVCTe=&&S;vv5IRgKG%D>vsnG)K2jkPBI`eNEmRKF4rK?zj{P(!Di5Yuy+-CcO zu;zB_RJo#bo`^gc6}pe&cYFjDJ>N&Hmwq*<(IXt(!Wtc*7F4cwXuX^g6=%74W%rcZ za_Sp?+5S>Zop7=TcqxnL_%#5n-=)`ZS-6C!Jpa2mgXqO}p=J(lLUFDoT6-5drD0X( z$+)bnZ&7sgL*AmzN14n^ZF@H!vD3H3`E?I}H?aW8Z~Ho;tROyR7xJ0+N9Ipel}Q z9+-Ew%PTn6gl&<2jattV$t}_sT_`~$Pg|@JFr!r%%Z8`nX7YOg1UDqh8{!grU`VG* zgA-rnJsp4jBK%bx{A=qe85^f0=TJvF=*xl$6Z}3fa%|7uuAt}f6RxS@(o`XEcbOnm z0l**vV&S@^(^jJ*!_!pRj7Sl3b5&Rv!g1lcWv?9ELIS++S6i4bv=k|G)?SqDo|cRR z5?3OYWQEvY!(IwJ03Zx66kx{`a4zII0Wc{7sO{%WF|nUs$U5id%&KO2!c5MkO%@GC zbnod7>zz?{Ey`iQau0MyUc-++QM*hOXAjW&y=ZnuDko*QrQ2xhQ{*5ebedq*xwXC{ z3GKEbm3DG{b4kpKA{`ewmwS;P5oj9mcZ^)#eBHFt zq}ygPqt9!fB{nEc`JAz;|8@NB_Nzb!$(f2zh|QRK8!xP+dSKVOoIwu#)ehi5l8Cct0tE(b%&c@2C%Nw)=t;W*|~Mhgj0lf5-w7NpP96T`uKA}H{HSAwO)rrQO@7mWrbX_c2F*_ciZ-qQ%)xSty&5D%@#Y$lG2DmNbMRDcJ>Ci{ zASB}FgaD>}Jr$&Ul*;5h;>mbtE@?&_RCAB*R`?ckjF+VDE*Xy;^YOQwOoulT(|vFt zy}n*Km@o%M_#{@i{z|;lDQDXyMybp>3e~j{Xixi{%-+QDV+6l zIwK1g3NN?{oJh38sCR0A|8A3+72IKk#YJFSYnjA)BSWn1Z$7K;S(MPEwrosB=Tm!fZ-3is$9eCIh9GuD{BJ5 z-5hzLt5k0JO_{HZ_AdL5cIXy`8oq3kWKKQ#ajUvoXgL|JPw46&kx`ms)D!67X%gZW zf|m{OSQFIAQ4O9i@yWE2%0Hympup)yRK@EBXo(L;%HT@HImxMu`!QENdqO6&An z@UTu<17`Z7uQ!u3=2mx$3#-IJJDk;_gPa3!s7$0K`Z=GR)`_=#`&2`~H5#wn4mmO* z&~YB|yJPD`YDxA;z1!;>fMqYPeF{khJn0K}%1DQ_xL_qpXc!vX+-%`c%Pbj!Oh%y$ zbVsk{Jt*2yqjSjTlKlGpdgwP_k=OV-w~A*yMd{_sPXyVGoIBG1giv5f7}tmpQBb51 zj0@q>)h_9w2aU(6^_R;{rbAMYfG0<@dWJ3IBmDP!RnCTUZpxcC@(b@Fh$_ccWk2B- z75(#{=nVG{T=iR|rdhw=!O8dvb}U{(ie$SaK3>DVc?UM4q%)R-8CT_P`^6I`)x8#a=F9ZhBs9)%z2eLc83#88GwT@I*LqAn)p>1 z?b5>@A&``g?hGQdV<#lXz{gK_h_<=P<=zY=(fVXulc0)6v)T@9udKCqK>WZxPt2rG z6f08n<#Dpe>v+YFV4m$>B|!G+Y50o_8my2C0tRA8mF(vsmkwI~c^z+$!b<*ibmt%o zLR7>JQ=Hb$gGovc+&c=|O9`#Or{V9~Bjk~d^Vn<}0}nbvuTy;m(>@SJXUU@vO^pX0 zie*c`I~lZJLs(uUHp}am)gsYW37NH9TjXA;z_9b_=?cvT>P8xJe|qw!Jby(1N{qSC zQBBY4=SU{7%6II>eSv}oCok>*I!yTmDd-dcz=V$y=mHD*(~^z^Cq^Y{md2MHhC09h zlutU5+H!{Y&{>{(@Yfz_`1#R>%iKOyost?^PgVO*ZR8F3#0Xb z_KJgwk+LH+R}&|Gy?EHd3~UqkejIh zhJ)&SYC5QJ361oEVdTW;XL|Yrl!=C9HP{wutU^PRyg*t&XH#K0F5h(VsGR86KSoUV zzE&0c!sv&79#|aj11zSEeJ(|H zLWlUlGfSJHIJ@#F5J@@g*S3;5z0LDMUn2N&Fn~Zd^n2@1=`9vXsvYe|jRm@oMA@gFdQ5{K~La7SurN6EphAPFg55OWisGpnayxX^9E2NT_2l& z&f&F>S~&zFN8dQU;+gf7`I51}o6+(al6l?rqff9eTs@(Wwvb&}^HkH_)$Be2PUuO< z7f-Y?B>Uhy)_LV(1J)w=yq-3)8LjCMSjiwZGQ7ku)9A8C4X{#A4=$$4wf^5(%6U-l#-zuh=il5?e6LV=*^~YN6crT|P z*ls^ZsJRGMd=;W%%z4;nenFo6{Y*!qBTdj#w+y_M8U9TKcG2F}_BAx!{3B0pq&HVP z0r1tWll0^c_dYH6Gz;xM7fPS2iH0-~(S=?8j5#*T=bqB(Z4_rBUB!&TGp38`4!s<) z&kE_#sSeLTwpcn+tPyk`wX-K|XgArz8jVctk__ELe!{OPdl`lbv5w;?e9=-q6=fCL zAodn^!s*zvQvK!1euN(|Yhgza_zYoGWmJ-(6ZVr0_t3SssMpM3e?0+^ zz!1jN30z|3b18SOZh3Tkt#C!F7!+4w#Eisx&PsfoXdiEWl<){ddNu( zX6tcj8-fRnS^k+g^|7&wl8Un%ugbgIs#x;Q_pw{(t<3|_QzS-PjX!vPI$fEJA0#KA zSFcPYC~IgYs7q0Ac)9*k;KzKZ6GLif*BL66J~p4cC`_f>=+yfXd53k;dGkhoIUL`w zE=+>$2E(vJ>u=MADF%X}jFCf4gbyyuO@6x~{@pYxudsQ-owy<0*s&BZ2L;UXVcTDo zk2eW^t|Q;zHp&(ls3;|b)kgJBFR@{@lR^aVd~1xc{Z3vcq6 zJ<4n*JxOk^_&#M86P?xnI=yG7r5U{g(e|D#mk`n1S^4S;Fm=^Z0CP7``rW*!Z|7!b zDx+XaFL7Yw;|hxRtzj6rUvaP;guV@iBfb4Xd`ATOi0f;{Kv3q2kE`RwQz;?*F3x9c zp`UBLlx2uAOk~T_(Le0;*rLdF5k3|i2Kw3z@}(MY@K3r0Ne03r_h1CgDmnDcU{J@2 zGUd!l;$&`1uV3T#w{jW&fN4bRO#3OcaTTK;+BG%>d=b$0>f9}!dv`Pu?&Q)PmUwht=pUd286B;z_rKj$4Gy?)ZQ{^Fh(&ptgZEvJ zajwWG4-$vhTR}7H%tW#(;y9t#e~gV%u!c8)g_W8kgwsU)cb9$GA4))BZ4c+TzEUNtip-KNhp2y-q2A%Try zmD*+*w1J=ZbM^CkAX0Q|Dig^NxWtSV4dcPD6qrOmb#w|EPLnlJjzV7hi4_cxpX^Q( z712da-6Vhl^`&!!f);~7LUzydQDS8+O9JGZqu9cb!7ip%wsayCz0-fsKVt7x}GZ zcKw;jYftGF#1VaLi=YuQ_|Zy2wmTfJ`M4xp2k;TEHWSa0*$v*Fi2O~05KnB&@2;G4 ztJFumoW*7-3ke%0pTSGAb9kLpDo1Xkm-6glNVWGFW(LqR_XZg&_Lwq9Ps-{W_RD35 zG6kywZGEO5fecKpm?5zaXh!Z6q&Vo#&WLf-a^5y=&s`f=4gV&Z zP1&C4!VO8s{t|xa4E!o7@dGAfzzDIA;uJPA2+Q^9Gml{sxkyFIM8J16HB30p;c$XA z0hm-|)RxaG_8FPk+b2$NL4mNllQCZ3`O87dX1Wv&Zs&L{s8tlf*h!(Ugj?tvYU1Q< zjY%wEGq5!F$)k#|R&EBFxAo5^g~ko%2hfQCd6@Zk_$w?3r{eJ|30+jN)$dA-qQ6YO3rw7?4T!Hw;`EvOqk=& zLs>g7?^(@(qwqNki6Jn&*IibB?lABnfsBgsG=MGk#sQ7!amVRWhtwFqlQk~IA~Sp+ z=CtPuF>-M6O!t8AmYAT*i)~I=SZ;Ok{V_ z?$$AkQ$IVDv0ndz!>2RJ@xE}^aSK=WMZEnOu06@>pLQkdU+TW%Yz5oGncm+nbi2PN zj0!zA_J|(Qcqovbc|>>GpfPk4LMjUz8Pb)&`B~i8zbkmVz;79IBwT20+x$0wsB36} z$mXkdtBO(H5gne`1||Q}r@NJtux}o;hax6wKaOeYh_{XRI*;~@MBbjbXY+}PDQaOH zqsXLQ#q!GT0ok~|-V3kopD-1LKu~#H-;t|5ric{A?S0qiEWMOBIoyfj&*^P$p7$}X zZQQRo!3|)3c^Bml#HoM!B9VVgsU{m|6Jb#zY!9vkVrHlcydc61J$hljamLB#OTR0u zHo$5KPHoIS$@Bwcx5R@rw^vMak{||My>OzPZ7&SglaR_qiB}MaXQasu`SZ758h)4r zOTlB0bBP^vV7$|n8OWWwGH)+}1TaN8xGcd=hzQ@FYF?j4erXuMp}vCgw}oGK+(BiO zG3KTTCm2&u9``yrb2CDwf12VW9ZYRVzA9X>XIa}yl!)ALSuhD5A$hVpe((J;gzYYX zKrx%rT7c+Fo;-6Ds>^%XO0qzTo=H+Vr9!f%KKH~H0+|S3RWCZ}GkB^H4jV=ZwR^n& zK%5pwnJ&(ogxWqjF+}cY`uZ*v{25HF=8%pH2rg0M*UE$g-KIE!@tArnJk4gj^~gl$ z&*A}|unaGd8rr)O-ADRyVg}uGe0ebJ)>OWw7Vc7QAH($d+M~2Ydl3PI(UY8dyZy{B zq!s#JHC8(=2ZUw71@WR6JD0^%r1oN|^;Z#k4JQ}%Pcqy|{(;^DAfOU!C z5e@~OZyfcA=#!973q#l7zw2!FRt4=}D`gXGvD(WV!8l^rRR3fOLu5qfMOG@{WarBZhBi!(f6C>!;@a)-;=M~u4U9J*0 zY5d*F4>D9Mz@>w~$EM>fM`CScsz?q8Z_ny2kH%L@crL{lI!d-X0Bi(&HxnW9)y0Tn~!F`2Y`)|TPZo}xhwSFl_^c3smT{fqfz@Jqb?jp^lsB0!mYM}pdXnF zV@PC!N$`6vqV(PPky`5Q!<`=nFA2QNCxRAwH#0x_W4wHM1LSDeVI96KX z_(y^Y>wmH@1Raf@sf}#x3;F@VxTtfAx*Hz)^19v}%2gOWsS{?2d#sQd@D3=eM^d&wJWHWxjwd}MDKvwfl$DWzl!KX7=TDB9fsKW=`+G?! zX~otNWNqMN@ZqoL7S<-rP`>9gb4Bsb6IlZr6M&G6w79%9-QUFjeRyc zB?#PlFiEkWnY9hf2d}wurJ4Hrb=Nh>9g+H6AbNx3DmlK9WKtds4|%VDb_s@`!$WmZ zXz@`!5=BF1oPVt8>LxQb$kcrmjYw0#;$b3(ER#?(GLer^v-PA=^SZZcT<@1Sb~0rR zCgCcYBTWm{5To6ri1sJAaiNclRJ{|u9TybU8$};5CfijtAEx5jQX+6npv;WAG|ohp z8@QLEQrgObq||=&-BR#%uTvVn0^Uz8DD((@urZ-jPRqrX?&hTZBp;rKGWb0&0oia@ z-D9JF9lW%aHM}$)+Bwrj>4wLHpyou4j_d9xK9dkT) zlmCTv{D-;we~WeeM?K*G%sPIS`5&{6|36cWpWXU@r5ZD{GjjaBFGBf^4uri}-rH&e zS}saG9%iN$KDnQql4h7FeiSJuyT9;5@C$umu1^-TY~X7*w40&v`Ss5Gcn4gBgMp#E zyYt;~G~c@iBr982vx*+G<*45HDpMYQtLi!?&c`?m6J4{Zy0W4YuCt&w6+=v!_0(tO zqx|#p)gOoHgY)lKw3r{g611&pN`?lgA1H~R?yQwpHW#>eArjkzyWnH{1AQ-I6 zw^TRVCFO)VtxrE|+-;XWf)e>%nuFYZ4SW^`E?v`a+^1~@ukJQWrNzq!)BESX$%dCo zY2Q|y>bav8Ojq(*5jKYS{EjcO$(VEq;2B2UdP&B-jlDW4>6V=S;T-z?8=tKb)?)pik2ICt#UlOCL1HE~6}NX>PYgpyn}c`E+mcu^1KM$Z8U-kERb zqj$~GcJyGc9Q|6sdY(Mo1*{P%b-XZ;=5@pQVh%}tNTei}tG@~SyR}XE7u>slHT!;LEAV73m+Gmn_ z&Fhc`PNyed*?1u#n#M|uF@{}#4@W^Ji9}STcGS+jEfuBPs8)<+xK`mY zN!gl~M(5&C7)96b%TAxPcLKel$U!Z(2U0!?r7~FYJ<;%3W2C642aS~ z*p}tJwY7xA!uKWwxKg{Fzon*Cspk zwrUg)b(TdPt{qQ87Y$JCFJ~6A^qH--PJUe6Q818=0EbAhsYVj=aqKR4#6A&*;^Vl> z?yXV9p)v6zXidva9+;-GAaw4{(#Ir<<|H;qfJ7pk|KXY*iM`#=Mp*Z(;^%|8LrZMv zum*3LYqeJe7|!>bA23o`oVQ@9xw470LztzSX*8+wP`A%0+z=smuV#$>I{?+A0o~r< zw6u*`F`DQX$?VmnqNsRLvJs-s#>JUy!ozPC1iK;NDgq9p-?#}hk5Ztkkp$Yc6y}tig??Ig&-d) z?gJ_`wJ~JmSPmxN9oP41t+^W6w^>m>mT!35IGv6eSk5Fg#)Ws{TiTy-1o4FwOiB$0qe^ZqS$J zRS?$vN9p67lByJ})ro4hegVp_{p<5(enQqEtZ!{dV``*3cGIx2V*5=1aU)wx+y!zRw%An013;qtlca!pcYT2 zc}k8Ytu`YG*8-3TKQTg4$`3jb`XpMwg`&G8oMoSyU85bQ$&&#@MWc$4M-Xc9PlCe| zW3j!mQN@oZk7!IusCKBkxH1P>7}F+B$~|zN!)D>FjHue;2NXBBD={|p#0Sk?6>l7Q z(*t>w(SYYtH`~Ll7EnqFxNE@c&=~gVHsi_fOqRV`m+@@WFgQ&?o}1UBlsf;PhOSPoww5MG9Oys*w3L6`SPHC z;V27S$eA6M@i(YI9NUofSmvxHDtszixGKeXmWOC3&$K0bLuz%c(}wJ8yp_|ZvU+F9 z+uEL>OrRC-X^v15#_9OM@Rnn^H zy5u(ot3y+{w>p(a@kGF`ohJBWWaa(a<{gl8yhQQpcU81SrV*B!_H%EcE2*jLUV`(f z=*=hybaV7dRcXJKn|i~7vB#Ty80W;a3^@(sX7Ho=G)t3pBcLhkp$DJ7_n$U#-Lnge zF*|T1?K7F*$63J}(1|_+zkg{^QIwd5&%zgC04UF~tBhhD=77(>Ip3%5h9Sxwkrqri z*k@yuwpLa_7XpmW=*}GSryKMX^fr42#wE zD+Ks__rVPGOZJkP=9c&T>0j%I+(fG~pParlY#q1AYM8Fb$9KLmM?j}nd5IBB zPGeCBul3mM__WoIHgmS&7}SyhUn^hPzIYp7a-- zRS|tkyyiq4XnM8ylo2a)@~Mtpq^N^DHu^HX()hb7l10&vU^kEoE98~-RAJS#845PU zZ&v-yE~nYASGPK{0HZu4&-Jb*aKHRnRZqSq@0ecK;nX4DChu**4!kLzUIl7L6jCxs!pM(!<{rr?kGCtq45Ky=p}z%_Y!P@NRKE#Q*X*DE5ned;d? zpmo}ZKtX&D2J2GghtNpqgah%FI0CcD=zUBI{U2(~$2K#%KKbW*SSAT+1CM#RWWO_u zxWX~+J>f!9@Vhfey32Tpu(u7WjCc%-=gk#q=~D#Sm^c4?@%e*|yYPP4A!k*rWp2Ip zN%wKgIO2_>jccoz{>EK;y@8;BFW2Cb7bn5IX&-mN$ji$dTYHv1W<#@m0xtnsd&ihx z?IGmnDRVeFe0=H{FY3QIc>AC<*dR8^2h=;vf*qY#4j5S_6&eZyu>c!oVU<$8`|Rkz z8=R+kUX)G-oa7LD?iqV^)~ABUGerXt-D0?$vUKR~6nfv*E1X4Ek&cs~1^x(Jqhh5mCR%q2zrb zn(D_4lv}lco)}b9<1+z(N`U*N2KW~e8oRv)l=R19MMxtfO0+;OO=S#sPnzA3QuYA! zH&an(y)6WPI&=b7=R|#p{Rt13&Of~VD;ob-?)L9A{;zK0ztec;|7LiY`Ts?D_^&hn z+cf@9l$e8nmEo_K{}VO-x9Q=(uJ|7*JrgVI|Dg1X>OXBaMA3X!YSKpZ5$ha}jQ#mI z?6us`tsBbPJNz2p8-+DC)f0#n!xwaWb~u@Zv<=X=MC5-#>cxmpxA~lKo4#JX{IIlN zk<*zb+nF{Ao;7IBT6EWj2>$N0OP}O#7WM6U`x)a_w2@`DRU*TO8umkj`&1`&I}no znWmG0BK2N0Vs+`Das^Jg%hh4-PS})ics*NNeZC*EQso;Y9*9_1KmjQcfS6@6HhE{Y zL)f@BsS`?L*2m{B3VPU{0_f7k+gP27gvA{xUn^l@ z71Zq?Cc>w<+PvuTHAYg4LS&!5)!*j(_hO*52*yt+3iXh9S#AVlhGP+}GN798_L(x- zQ(ZWk#gt(z0)P+$Z&>c1G2I|gTX3Pb>PO<4Bg(jbNJKdu^5b_9H zaO#?ER+I>ILu&Le|^Lt_V*8G>0D8e zh26BH3WfCn8|??s47B$^Je8tKsrk9;P=oBH7rXcA=NNAf*vO(BhUiGcZwq=zqyU@V z58&}?Xmz%sO+1p(q_MwuU-{RoRtgp13Kr`Z&}nm;Xuj25W&X-i0bp$9{~!vi5{(dH z203I2OA`7e+>plxhp%8T3Q6c73&;J&x4=qw#V@H(0w5DoyBV6&oa%<^+fM2;8lyKP zB*GMH`2JN{TE1Xo4@_;IssJSq1!-UZ`?vU`ygyNBR4+kP-j?rT-uHaNb2mUr+D^cWzZ3*IUi z2h7-0742qQlt&a&fJf1}mgx7O8$s-P=`VDW8b3Ly+venxVI?|~9iCu8f@-NzvLq^ z3iyl0rJf*Ay5UqxpC>++Aoe2{hiwOfhcvM+Lr^@+E3F(O4A@N9zDL{22iRdR3VGX@W` z%o~Fw8jDsDRAR!@IYsE!Lrp|RwSR74qC+zK$aLkdLuzK{2|)T7`6s1rM5$vPauy{< zz|_=0#0Vqr6)mw*U@~=%htXsB#k`6;*3e2oJk?~lZY`9GScLy}`rJk-2)50(K-{^w@lfD+w>!Gg^@#)eNaVx*H3 z;h|O^Ne>nixyq|-cf<{j)Wrq_w@G@&M8&jCZ3&EycMlbobW@g$x_gU#+rM6-4<}nC z`fA7GO=5s0(1a|_J26zJ2--nWKkk{6pP7dO(MrnPb}cgMedW#w`uCh&xZJNk(8uaL zq~YG1GzNKmF+1u$w4$^Dp=MF*0u4xbL;6-Z3lEtHD9QHILSp3|w})*GGs*54l(aZT zKLc&v+#*9|W8;q)lu8>y3O700E?8EyjX?8Ep6{8Wl1OR5c6$uNEU(6#XrmR$4JDn0 zpIWAJOlWqQ-9^aRel8HMd)&w-8EVRt7J=6+URQ#)DrY-8V8Z~}@kTwc>fHrgJ7tQn z+lIL52q13A57Ob-?3X3R_K+qrW_t?Go< zNV$S==;jIqPxeHjNGnlH&C|W+hs(W5tAOi&9fOpSXaSxu*9MtcU1G z#_+p-!)y!ySa^nxesuGr9k)7QO0y?fTl9v=2G#M+9c6>_$5KVeF*&c^MYJ0TAnvvq z$Udvxd-sr2_}$E#X(dLHA6H;&WXH0J{MN>ew_G1vjycj2+b&2?-(@4M;)-HG#ntut zv!~g7&u{K#1+ehLa$*OEVua26anF{5g=9V+98|#6gO65)>59ZljfZEhn)Jy?YL&j< z(g?y=3u+%`k3IsL@$-HFEgQ%Bh;e|>;}MhMUKI-l>L9kqKIrZ)Vj9Vbq&zw02kjV~ z8x+{%{S&e81kvnIn2l8Z(~FaiYkxkAJIuKCIhRDfJ4=f}{=~dkp|(2Z%y#A7``b0R z1_T;z-#n_38xJrg5DqV|zB$g1!{BnVL0)=5b6V8wUuT)lF{X`&T~4(5=#HA1wrs1 zir7Ci%m1N>G56LHIzmF~MZnuJdL2{1Umjp1(XExp^TN ziWOL6mST@|bwKj%wZQUbi|>Q#tPxT1-0Z#M}HxpFxu_wKSbsf=uVotyd7DW+u?j!su8c+w$gEP5fY8DP~5)Ni~RNz3gAUosi3d(N3GXRv>E%(J(Av|R}U z@jH<t?f4NwbpV4?`>c5`R3Ju@Mt5q#OhA2JPfXOqn1 z&g^^rLvIq~B!>gRpVO)*VuBT$iQedN*vV(#5e?A?((UZB1;0!z`E2Gs`SeDSzRsYf zSLVX)*VdMcZ_nY#`_;45x$}-s{Hnv~eC^5{WN;H*oVAa^#wk>?mI9wg#x?CTwAUQ* zhwi*B4hZHEvlX$A+Q<%~*T_MAJm%Z2mCCOsl~(~9x)g~bvp?|x6E zWN$!tSd4V?^nf3AmI?vQ<$9EpSsAARHa&z=#i=qQR)) zw2qcPRd{Ca@R~O@t$H{IpwdMpc;;Oj6<+U&CTgD>G1SpMTHOkl0o@&W7Sv2q?FA#B z+iab`#Opm9k!u=AvxOSD7^cf&$t8L{Xr0H#&Je1zt0;xK zrlmZOAS=82YrIdiE$Iw;#I69{+nm=DN3P7nr=i@Ty6FX|f-tNN@}N&G&(FDdJ-#}E z_JuW9iG~;HaJCB!vdG6}-^j&*?e)uSiL3;s(a&lzDgv+Xg%j`&uk4=ms zV;k{GT2RAXy+$Qjan=Cy^+-u_rABSRGfUP?aDwubC1%aaJjzKk>cXoxHSzL0Yw-pF zmQn8$gF6dCnTUzQ20ijv1aw#zR#cnPyqu|Q7KU#9!n-yHIXc_>I0wLpwOGUiNg&Lj z)t)anI+Y=bU+c*oRg=jXY+WzB7CXK$;i zYWfnjds>^Z&+KfPS^FS6-lQj)Wm8B~QAkU_%rO>k=qw@x3xZzd=Bk~k54#|^6H|+z zt9ltUWr$Nm_2}ffB987Q#K&dx-WHq22zoE%Zlhpix-9WZHUdBWRZQcGvsVNy#89{j z;vpW9_zB_3rquxCIM>2q2FbZ3dbJ3f#YLss+KQ1rs_Oi%_%Vyp6+XzJXqYGJR`W?u;6Mo%N#%bez21!4;ow46* z=mbPt2o>D8JZ<0Ytha2jB^a+VBQ8Fmtq5`&M_)bXD?-sheXzpQDEUUaX zKd%my*=#pzHPyE=$A+EXxq5g!#lch!zcH#(e2L$H>>o+_%!ryUfg-sDTSDVaRk0Qd zO|H&%&H}s&j5vHPQqb3XXFQum8&<+b4sO-PVQ!Dle0eur~22oHOkTf zh^EkdUC?)F9whdxwlOE);Lggc*hx+#J0)Y@Wovq%U+BUTF~dWWVMIGi$%2tHnM_6@ zKcbUR&afLcQlJ}_1#1B&JRn|sVJO!EkKOaim_u&89T{QDfS;VkXJ@8&Ld(Ha{~%R9 zE4o^qhoC3;b|5qut6*38XzW;ya->w9?7B01#y3F&G)(m`OKo3d-%?L?&Z| z@7^*OVoCU4Tn6{T)%eE~;(D}8mhW`IT92_@>Mw^VTaPHn*?bDBs?m&SU_0_dL*=~; z$<>C-p~?}ZWEoPR>3CQ#cVEO^b=2(dPedw6AS^=}jGekiv$BL@vo#XH+CCS;GP9=CS1l`v#-Bv+bn1N6&{oE-k zfU4lgezo@y#c=vSzALp{j7dqF`hBXSlpZuFHP6bb9}O|2z74!J#I?MYV?j0Ms(!0S zzU*mpYCvCSCY*ZhT59@Rk}5v8S+V5Bp_j2(5j6o9OoLgm1+QW^4rwg(q7c01_%5Ig z-@+YFm+(aS9KucLJnZxV`H|C;$y0+@QK((x*Mt(`n}yMKqSb}G{M=mY9nnX)*--*I ze_pS_5Z9RXGKTMPKSSMYs1SmO;hT%zrMeuKrl((H%+yg~o8nAHNx;Al{HmE)wnP&p zKFemMg+(_;aQpJ`@(||n5$+>7l=P&;>-}7cQ?gK^H>s8q7%`e;8wmH9GGWY9ksoq> z<5@g<1;dXA;OUuzR)Z)?t_YE7oNaFUI!;=wNhp{L3!FY!Nl! z$t04HUW+N?m}+N0lBO$Km2}F{Smj(!{Q9xu+r+@Ds{(;wadOj61eA8wz%0H)FJPr> zeUHu@Ue9{4d$bB_SRAZWY>6%uaxL7k&j2&{P4k0#^ITPKEOA{5g!U_?Y4YbeX3pDL zHqnt>C$h9$jaa_bDoZDtQqIN6U-BNsOn+Yx-;0NfL))H#u^lZSGd@xfuC}LBjf;U5|sByoZCZ_NldiiX@Xi)Fn zRH9pXYzkiIX7UexfnWeOIk!yyB`^D%cl0k__7@BL9}>qu&4vG+epKdvZg>3myzFo0 z$^YDs`v29b$ow}y*3-{+){jscqP7h$8&qVt>p6VHn%=-i{X368^;@1wf$t zJn~4!$noMLQe@9NFO$JZUgntqWNlj4lUbaOCXdgbC$pPvYaK_IR}SgvvotLY^YqNf zyFYdYjrUT+#~L@D)=5c#ioT0^uYa;k{(U?OP zf{w=%l!5-6F3)lw^!d^l?HuyWw=3$cpMFV@$=g)|dhE^Ap2jc4C!w&H`EdduJb5+& zafTy#G)3o9>>1BDp87yxfBE-ek;~QI!=}$bmC(Ke_iaTNIEM_dvQT9SgT=C&xYd!q z@yJCz!>G^@_>0addh>SL&&Z{D7Y?R+T6}Y(2{?&~OIaLq?kw$9mzWY9X#*+K5IBwq z_UcXwKe1RHVbxK4*NZwxr7~Y#ptLc6d4u@zHZRwT?OZX?lCTJu31RQ4Dz(b=Dlv1; z`ON-^4TsGk)@iy+F`B+iS{I{M!e!#)ue)9~S#|!hh=9Uby2? z%4-c+S+9x$cL#>=_N%I#PmX6&Kw!>I`QFL|UYa zdHFhTCMDIPxfd-ZJPKk8(ezyRe;QMqltx3;`XllpL{UOkZLp8R2PbOip0eR*yAQWp zNe7-^otW%gmKU7yGC^;KDN%sb#yUWrjA;n}Ee6C9w#FH7) zrfk3-4&q=ze-dn|6W*%h3Si=3PKh-$GME5(#;u>0$YY=+PKu1?Y^tM}$t~b=P7>#a zQV<>8?*xKzH(c)Mdm68gP1VVII2X8xG%6c(jx5D$CLy zl8npyi6(ZeCibv}I;s_AeH>}N(gSMg*q!+C&+`byqGX2nr9Mp89a!$QK$HdXK&8gv zIKD9jzm#B6#^e(-F4d>YC>TTGpxw*kw|Ss%VKxcYF$B*9g$*sWYVxzg69q0(nXM#X z=R+Fs!K8&otU|+d<^|3+?ra*D-oUu&EBGY`Jl5r=CUJTvf%bFGOB92DE}85eIR z6|w?IZ`gwmnLRon+B`()@F4ly7c&(K%jHIlVJH9)SYlE^gh!ur;C51fLokjjl zvWq5Fb(YBR2K*M8`a=VViQ3Uf))1GiYSTuGmnv*t1W*BtKTa9n6ZP(Qlsuj$1R zuk4$YbK`?a|8e^HPdUEri+GabDYH`Kgyzjpm)OhT=ff;F{Dd4kBix6d$5E&)gz;WB zq4`_VJMhq^t?o(HxY2YiZ< z5!{8BIz-}SuRi7`NI;F6AHvL0gTeR(dgG1@#LnqIIe2oOBJ`9Ys^*mRYfqDy5PO}`-+00?(*EdM2v`CIhhFC_EV2>9gT`Oi`p*Up4u(IOq5r2YH%ooZ;g3P%50ZJ@U?~i2oG?i4F^>Ik_{_wgrojB;sjtNrlL7`;y~%y}aY|tx!L5eQx6O zbmeuOX7sS6LJ?>P^nDNrr-BLdFrB(y`*vKuNK~s>LG`)zLnm2Kyi!YR>a@(@56aki z+q!e#qFc|=rcWK3Ois9o)G&8naK3tu@7l0FtvG(|+wtfyayzN;?lOoPIWuHWN4mE-Me zmMX)jBtW48b`7n>b-gbjuSGhPXrju`Y>Q%kEQy$K3|CQcWTo-!_= zDA2(3V?GuThne!u108-S(aC>G**tqe!~E)uBVP7*9iUH&E&h8+BT$Ibc76T4B0SK! z06(d==JUb`HkrM0En0;{8c9G1#GB0EXD>${E-+&d4k{b)P|^g{x7R9991v<~uq(i{ zUZ@IV#V<}z3M0_bZz{7++jjAq&=7f-4^rH9mY<@lw_j!Y7a@<~3rN@xFIEt}H9=*f zuU84_*qpGr7237(S~>;bW)(pk*dSK(QmRqOo@x+4z95Kw^xkyKzRnW&~5D zpBz5f&w&Qxo{-RI^GH8JX-n9E$cxBDr`t~qjwLokI*7(lY|$kuF4d8j>N%jTYAYlC zm?0TnO|xRPci~}1A||7lg)Fb+zWB+=eACc1`=Av2U}l0BIdXaxvF?H_iAc(r>jlQ$ z6!Y=;!U;q_A9vlxFA@_7xwkzTc9iXGXJoe75+-j8;(%qk6#d5()tT?17-_D!W*>P+ zabKC*j+XJ z{2fbLZA2vUWc)xP_S=7D+dY5m)G+&j+So8L<5hwes9`pzy4>R3^PA1#;N26(We<%cw`G6}{Q z%!G9$!;?+%WaKiLVe-pml+##>Lb98h-xjPv@yiTqzQc3dx&vdGfF`(|4UAp-dOpZn zSN?Qj4m>E#9oU01B9BuQ2AnJR>IB9g{q+)1;=NhIz4T(kdaH#Kw@Vf0SBl>fQglys z3rn+djK<#lr8seF0Bl5%H)0pylRykB0nV#N`)Dow5z4#o35s^~`wJ44qj$G?6%B^75?Qkgi|?O8F?L;qMZr zYMlf_0!=|{!~r#FR@}DY!rW7pLn&g33+L457|IkA+?-t3_wL(9pEqq2TE)bapupUa zjy}ieF-(3O5h^#3Pi|f~xtCWlI37dxbiEFbw$cut#-(rvgyjJtBlFH^cdR}g*@sSK z(0iyeA8B}0CdaRQxs-?X!=rvR6{6M=MK?k-yTVW^6Gt9-Wd-}QkDHPQpOd8%v1r{v zhHqEAZU$P?uC=rS@VYR0vTUM63BQzblr>?TWWKAM&?BQ(Cij(bi3ba{Y}d~_;)K;` z<-?R1mlAa!6axTGc|?01o$)l;*HEyb-z6pzl_E=rbE;9SM`=z3sbt}u(bLhlU`Jyy zFE48gpk5!zCDiOpTDe-hAs+ILAL+iLi3b?u~mo^<<+f897tLvxY?CWFpK|Du+bV^0yx-lz| zx-`)u>lOQJ(L)VfKg8xaW%xp?T;4H?4W1)mC32K)J7gl4ty`wT#B<@&_>msQQ4*6x zE=eNwezMWt>ZmXy!tz;UtMel(GKtrAToTPALZGT7?W@bvyGQq^9D6sfazg3z_l1-N zImE@4)>4-SZ5Hq5hPHq%VVfd!r6bJM3NjXtRZXoh=L>k)Eu7WiNUlFY$dZWjiZcvI zUD5zOO)66-@FMApRhTJY8B&*LDeU{$_-GqH_x!}?atgWRJu3DSWzk3L@;G;(RD{8i zD|wUPiF>Y}i9Twt(!uq>mWTwpnPrt)F4pUs(l#U7Q975$UREL&;*WxnCf2>5Y$>cJ zQ~b&7VzQVZW1t{xSsMK~yZbHKT3}S-l}8C{0R-!wP4u%PW=br8@Y)rv;ZQjV;WLE` z8VYG~N8#;O)(3E~?y8BC^&1P&UIFHORu$Cv)CIRKf+=veiL&E9%vQPwBx4*yNlc(` z=DuX}$4L?5Tc>xIj3M#)wX%{AuG5pd38D*3Fq(}NjZ zRDH4xyXQtv*;Gj9cEzy5KmXcXbi1+CDa_!t{B2Q_h3TgflbyV0&mO_=Ii&{jZvBHL zU?zJs561n+1a?xrg<{4dy_0}T@gh=ISi~-_ZD)}~GdNH46=A{BdRe_Z+~Q$=n6lL< z{-gXf-ohY$H4U~zBXrPBw$BNh?~_@ZqwML(6~+gsY{Qx2m?uL)uKu?&9sCT3&Mk}# z-cg?*&?s&Y9~-%Q(PC%5 zxD)eDyFKx&OuFKYc;J9nUcT3mmVJQTE+FOx2*Z z+}LU-2Qi%dCUc=4v#iP`GwJ~mbKF$&_hU-&_pNNR_g9dz@mT)VJo{tMjqF*fFeS37 zWGpxaC|bBj(i&ZiR@6_=c6_T``%-)_4+@WU6tQ%0#MK~H)}*y(RrC!tmGjrvDo^|3w)7VNv-XmK2tMx=8*@ zgyFBp|ND?O%imlw|K~=Ze_iW85(Y+2Hs-$*1~0X>n2lkie-H*@%(U$7RDc(KEB62p zdz@7$1cFxhdf_RAWwiJR)}8qGz87Uzr3q;(m|yx09hSV#<*%Qy_@thvS)Z zB$-uY@nRz&U-N+qIUT*74_er48`7<4@%B}MUz|MBtq85HX)KSsYnKy;Gv`7bW!NJ! zO%Z!TkSSGtYzOLaE48_z%My7x&y(TxS-qiS0?Qi?bmr z+(-1cmg<}H&k4Ucez5RT?7&P@fj9A;c~EWZRPU4|pVWsu9Mgfkl$f7`wIgG99xEj( zsRnHY1q|y{^-hhPmNF<}Gg6AK9DxKK{%RdSOF?H*R zdEHNy!<<{DD!|!HKd&KN{SPeW>RmcEZ`!ZoD(l@^`rR=!gmW!89MsTi95w+bY`F2; zvxc-~WNjSjBGHi2U0YbS@Y6W9;v2dXoD&*;sZ=hr`ow$!D1Wg`*{6AnZ6j|+yt8$D zRrCV^*eMB+$3kdhy?D`}W=5W{H@l>fi0W?*TkzYrnrSF>bGcp{h^HWIgG|iY2j`SxJ%>ZDvqtx2;m?To|4gQ#tG_Ga-O0F4L^1Nw841AEw&-`vlSe+K8^xB5+%HVjAg_Z>D~DTJXeYb9 zId#{7+QAGA2LT}-2?x0Cz^HWKpQTln7xvvZnkuU7VvDcNhR>)7 zHoKwNqlaihCfX5SUTtnf7=tbuTKlx2FnVO}(Tx-d{HG9LK@GibObg64BQ* z+MpTI%mWSB3n1CwAMJm2JNF8$tcWnoXjLefUaUmhNRWDEpP zR+qyT0=a883*tA;Lt3J1qI)Wm3Vbc9T3{a^ShYe-JdN9-cytHqkXM}S?s|XCkjPNf zF6{de3r&uZm>G1h$XC$hNUvhJ@b%ORm?$E-oEHZx5IIWrqznTAq{CC>1vgqK?MPuf zPbO&@N>ABq9qAjv2Y#w^-t|~p?RX>O3I9kK45r;N;V<$V%DXb0c)jyAOBR^w_PmwS zo6BJ@usBI$FGnsxGlhO$m+yG7%Y?u;*dKI;i1|q(BHm2r9$y`5F;K^G2sg&Vi4K{8 zDE7QQSCTqSF@4+-ySw>pV9JCj+a9@%HO-&495(hoBkYzJJg{^3zIj|sYQFh7Ci72g z!E392yic|3H+?Sv$LwtBzr;F!bDsW%b^eNe{g2`3Kb6`464v?4-TNP~&fk>h|AScP zZ({QQTIOYDXJGm})=BzPNORcy56kUty!6#92)|$9P9r+0>}8Xst5$OP7EhE3N2rYlmOhQR8u0&?lw?yhfRw=bh3C13>8qO%Ix229Zq>3fX3k5)PJ+>4@TFuZ| zI7!5ukU=_$`MS@mu*wzU>tcjvoJlc>D~F?wN%3eyM#MS8Dxp;Yu}y^NMnq)Oj(Mxt zG==UwZ#cSo{=aB@rzpYJY+E-nY}>YN+qRWq+s?3U+qR7i+qUhKwQ4`CYOPM4dw1LW zeYT0G+511f-bZ)IrnYE%Yr*lhV}|$C_5m_Hh7|o6koIbVG!xV6rCWR&Em?+0iS5%m zHYI|8N7;;&h4`NUqYHuey1)>KS|=N95kQ&Swz8BYeu!zpVkkq@|Y?f z+cQoF$GSTbDy~iWUV)0uh7@VfU$bm@uZ#Dj-!o<9O@d#|jh>_wa8CO@_)1}a&bC$_ zC|6{A_@b@AzcFc_WR{< zSYRLh!PX5PGA6z3t~2L9Qa{j9CCt3PEh=!0Y`H$y8ovQa1(Z>%S|NU*GQn1fTL0M2 z^nT5;=Ts6ayruV(Fa55}9QMb0GH+fw7WPtd1bD98d&=VH}3*vK`qSSUhgSlChVrcfI_xI+8;~ih}YwCA6-~ z&8K3F*K!zIhS&#Z_yQx*$P++1SNjppn+*}f&yXw$X25>Q`KY$vL?Qa9FoLWw(|+#8 z-ZF~3BorI`Bd1x;=_N!7ATGosw1~J7zsmVbaL-^Rs!-~9ZI|&}^fus*$|$6W#jYx@iP2ieJa zB1XFOUZ?k~VMqE!Drv%^xee$VJh=-orN~=W5RKyDZ68xN(tgG{B`;;quCeZaJoyYk zJ#qAUNR~pNEECg^$o5qVv8y^o-o~tZ#Vdi(63${k^Ieo zAcfJ$PE0|oe}8Oze}hP#A_`#H<;8&bi52h~Jl9Lb04|`A)w7=ES~+NKHVoqilp@2) zFvkr|*yIAmR(pR^pM-Dr)Eft%e+Y}2IgGUy1Ku#*>Z59q%KY735lJOh)t`WkOVa)KKF`16(bl!redb~X> z{+SCys{LTq56a0NZfZ!o=n%n5vlYh3Y8Inj#hY4d-g4ZF;=L=Rp8oh6Bj^ydxNUu3 z$l467k9`9IK)j~#PWp%HQ6cV(KUw>Z=J=k3 zl-!3vd~sz~x2+UR6J||v{1gulDfKX1*6?k_eh;?wGl^yPwQ_OR_(Ok6r8jRCXBKPx z+~F8wQ$Mh!^I>ywr&oJDj8JGf)~7Uq1fmmmZN;z)g`UQ0GSP}exMFo~1_*^w>7xE1Sjb<->U+|-^|{F-IK zgx+;Q9`Vb?uN=jzEVc#p0&O;Wr9nvAgqOkt3Ap8|V=cQ!*egz!v|R_T0>V*u0Q)Fvk);(JMVTnNtgy;*Kv2k25-hlVhDUQfe(SOG z@V+ZO1d4}}#mcPnhNfm;tNtC@m7&>e2}^K6g)M7Re>PIiT%EFKvhAVGfn$>XZrUy2 zAx;~&=rvZgn-NXHTN6_>X^Q7=EEL$5Tq8CYN@&Kfn(DJUtaB+jzz%leoqVj##c0=8 zWIB~N*z^>V(3@Zd?1l1>v+(o5K!ki*0^j5m9Z-V54+B#sD8vn-*+o-!^1Bd63vfI# zEe=J-1kC->BPu35M`B|sQYkK|g6q`mRh}9C#^Om8riSxGI0%yz2xqYsQwo%e6`RGe z>`P&5fg+$bkF903nzzJ3-p46c)s@x-9R7>_C+oql`;p4x`FX2@WHO3~(f3k)90g6Q z`ko(phKPW=m8WXVEQ?YvZ!>pw+IJhwWq#M>H#WGGgR$C*>5q>#lSt(^BSDQZ=& z%$8lXY+l8wBp?SGLI|+vA!|Qacdr200tCXBHoH5Pqt;fMMd`n&rP$Eo?aX7MJWC-l z8WN^emrA-3#a6Xp!WFY`Hv;{&qNQj28j02k-gf~dHL%YNNF z=*EUp&4yFW#*q-6B5J{cUpmM*_dxjK+i4Sved*>&J(`vXW!WrRk4CS>3RPqrlk9go zv3k0&X4mweHbUw61y)4petVr?!^t+mQe%cyyMWR3_z5M)=^&_Z58)u}afyo?$6U9^MF_ zs1E8lWv+Aht~D)$&h%<^D?HtpeWNYJ}=lqsF{l6cSz1fp@nzv%M#SOne!9tq9cA322kADA_vL!8dj|O^ZvFr;_aay^+g(%Y4#htNg^{vM0;C0V{Me;?uG9{AWIdOwA1VQMT0GKV^b zOkTHY0x|Fh3e!wNwTUY)j=SP4d;~Ns4fN)o+s3by;ll?6t7- z0$=A=NU;Hw`q8o43OyWJJ$6he-KHn!zKXS;ClBzNGnB`hii!6n9qnwZlXFNRi`jdD z|e*z{MIT(1>VMUklDREBG$1FU-MBU&n^CE7ROY7>^cYF2^s6d8xDG z9SWYABY19Dy=N>~T&K*|&3=SIVj~h|j|#jnU>~#{juU7+l)Y1-;a){vq%4SyKZ0{b z*+)6QjkR4nsY}hnyG64GQHlU{IEN85U66x2S(7l?J>eEE)bx2q_l4$ojSn7FnX5S{mb_TDg8<&zFYX zq@SQEJ(KYv22QcM$`<7Qb}Eb6pP5L#=Ld=?(s_jtHP_qns=-# ztu4XU;Kz0Y2gwAR@?>{}VP25|w|JJtu4O0Hgw*N&i{oS^+{1Zd^AF}QL zET#R=Ow->mtN*@j|Nm1!^VcW-KgSh}46OgsZ~Tt}nvG!;pKU#cn1Np7BT)zSUbuP_ z5Q{kWBsMeuLb$|as=7_Blth~E$Ro68u48C5D)&od5zIn$eU5|4%=OF(*Q0aWEe&U` zN!_WRdeg^A^%mWkEFwx2fp~C&7~!Pl?d4E-3tl`_o#x8BI*C1>mzDIx$`(FCf$|lv zzgA=3tg3Zw8@Q2^bZge92q&nZRa8$aY*vcWWRmxNPwIQ7zS$=Nsialhla{OP>g+9i zWRYnS(ij<>X9X)xqW8X^sdlZnf`be{aeeO4Nlp=2SkF`1 z*D2A>s?h0}#6A@?=U*vZ*gP?JJv&O#AzJwv2x;+=Movb2xPj&=@nq;6t_%SCId6VXiRp174Y?N$BRZ)|Rl zUH_*xDrz^|Yv>FsbWE2K`r*ODy~ps>XU@uk6$UF!?XoYzDZd3%kjqXMYw_J>aRA5? z4##I)cV{q2q-4$VM4l6UBtVp~=qatr;0qRSK-gG}Q%i<25YD}tWI72Z?3}eAQ0`C4 zM!Z&jnJi4U{qcHUpWpzhE{RUkwlZK$5{o7+oLag57@c7rWZnqrV5~Q|qKc=Pj&+EU z;GKewBS41yO^9Fq^E*!6iJe)I-NK&kuD z7z3~AQlEIoq{kAwD@$g-IUH*-F=`0<(i?&3kxC-=i$FF~1!J9qv)e-34;({hh}Ae> zeFB_Rt3lvV&`B?9P=q>vP9Mk{FaMha}14N8r?wvf6^0hbTE&u zI@={S=tOA){TZ?#=h@f|q81n9OswYMaqO89)ifmCg}PXcw6iOGC5cFO@(+tBC6M`alyttJQ%P9gY$$Qnv$+L--9dl7`iz{%Vw3dLN_-w66mg9hE z>&&Zqw@n`Tl6BWL#$@)D@LTaZnDT~VXm}DAv>eVd(xNknIHuL)zI$;;PJ4+*gx7I@e`!b_pCfMtj4M8mzpU4ZsLHOGv zyd@;GYm0D!5poFGR$)hS7F|z+g2g2y_j)*9>p)#N6ev;JKI$OZP6&finCcwDB_(-We6~a7?)Bh&? z!iZ9RgmH_^@1Ch07XKop7M`EC{tSp045wdMeTQdJpdLc$X%R`|q!OGeJ`Ft|g?LbD zFkQdehpl=4lb-@13W$b^QuWg7Xcxx6Vmzju6{8l9MGB6Q{BbvegO_{9({CbdB=548 zp)H93tQ6v?>vLYBVGV-a;|$h3f zG0nR3kipFTcYt<~Cx7hFssxLL$>(Xno~0Il*jxctsjNz3!mVyUkqO5HmwUrK#THM} zR7&{ZkUhhfi9Jz-RzoYWl4CgTBM%haeQ#5;9z7hmG%WYHQ4U}hqw1wE;O8-h5j!Z2l^ z>1evb#hg%UUZjiZ`5CumxVgdSO^du6LG>Y}adee&HXJsh{ZAjFW)_EAMjd%+ie+gU z-4?gJwFTflZv8$9NAYC}+GmJC|aK_K6@PamI z@WU+D2DYKwd?qdhWs~9#5DY5$N(#zCh^GG-4c~DgsE;TfQyY1fZz|LngE6#nz zmmB6eX3>CCo`oB=3;3a*h!y|SINdcRURLfR*<1@xj_)pHhM-s)JN0h9ZQQ=$MmoI_%Vwg3vp9 zC_F!&J!MtcNTQPP)v2M?tytd`RZ7Zb7rkz$v@EYeDpKw%=#K8!)R}s^&cdr%NxsH} zP6TJys+nXqk$L|#>X+Y`{Di#L{IvCTRY@$Wn)GsK8Axz6{klDCx%lO!YSOWR!mIU& z1szVyWIHnChJN>lLU(6@a#mPsVrv*islKeeNat!ZFA!yWdo~ zdl=|)cQo=@se*;;dUZc}KFS#ISUhH0-u1#>ILa$+P=pOIlND*`KGBSm$?>wr)IyCC zS4lS6nME!>8pC+HW;-3f_vM?HR!eVpR3Ix-plNLts`Yrz@V>HBZeDpX{YX>`p2EG? z&{5XN>9~-(_f+L=qVt(P%r8n?&8Mn!T@V&8zp>{6?^4M7wPBRNK*!XE0|tuqGeZ{) z$jLuvNQW;KgtjlCu6#TCh!xfqi)rgwG}@)PG<`{km1nIu!J0V$H)C3Gm$6}MT!T<6 zVW?$b--hdfk>P6cW`*vxdt#~O{KYuAOnVRE4W zH(~Befnf#NROwdS2MwSDpUrxQOuDHPe=;fSK9;Cj-UsJse7BN1Pc&e+_q;9E2=#D@ zJ;Opd18D5urT3jKj-3YFE_^p^qrYxJW0+0nmO*?^*?0WP3KGyS5n)@Qme{)V%ae1I;< zMF}~cb^z0UG}3N)>mYp9b%u?hIUnO1C&d}59l7_om8y1wr`t!82e2MpttEN#nyB)p z8YHE&si@hl2l_}%K(Vqy$w^J!9yuSPn;dxr62j*7Or;OFUedx|>{W%gXhYwZwZBru z@j?~x+tS8ZBMz0}MGa&H>fbjkv+&JXr#%-F;Mr#Pmm0SGxzF3O7pe8Ma%I;Uiks5s&{PM_EVkK7JKRIIGk-yg;8A?s zFLqF-p4bj-AWJ908^f&yt2Oi4_md=NF4wB`1#{qe0tBl#C2Jy4RrYsUwYu|dxu%LZa zO>E&$j;iama=>2_b2)cCCl5Ww5Ez4A;oy(Mr#O(eY5IQT1@+Ed)~M zCyEl=d7*OYuCFZam;iQTaSVnI4Kcl)QSMMKqkXOel*;au;D}3$H|hNm@1BL;J0E!@ zY*vPWCICH(;$kRL4#mlO-lLW4JQT3RAHey5s~2H>yiwZBkdd=aNd|jO&TQ5gvb{j! z>mmN8^V5iS+D17*B~|${%trUrQ!8GK%kZ<|^L^Ba&sZK|7t3aAA&VB<-lmp0h3yFK z3SpL0j&KVD&`T0dzp&$NbON7w?;~wk8ino4fb58ZRSdWancm{6(vdsM9n~;Ez@nqi zxVHP1{okE|QFe5a$It{}cq5oq7pF%-Yjj4el#fuHrt!7zX1z?9{XYV&!dE?$<}3JU z9Sm&@VdHm`u$oSXVx>a+zi}}mSL=d5OFmApa_7^=e^f>bq-iih{DR>l%8^HB;w97( zh_YSyNVv);Zs<&X)gZ?NsB9?)2ZiiY^exA8AV6NC0dcmqcHG!Yl^4 z!;BkTbg1{w>!DU5*YPL!>O9bkr*L`c>I&b$@oK7~-GA*?gO3ZD?5fE74n}n^Gw8q@H zwkW1UJJm?m@I!a&6wD!vb$+^;a4>ZqVh3}{#rV)&ADh`0@9m2L(fAksI5u_(#K6-x>^ocg$!W2vr$9}WE z60{FZe#J11v!;p4fI-5_t@M~%SYH);l&Eg~K5Ctxu0JJ+N!a5@?bMtk^k9thB8{DC zC&s>y#o{gRT#IXZ@4gGBTTiy0J}|20i8R0zh&!z|{xEg8){5JLEhVo|1~TJShS17v@82(E~p6CcW;(AK-W_87GMmR2|sneQMy1m`Px#fVUW|u>ChgxkZ9}2 zk27EOjrA|9H&R^)Rg<5xLcC=H!4U} zKi*p8lqX-2C|yJc@#P`t14CiPyJg!_U}|-su7;Qw;R6__T#y2T6^3qm@bUm=bV_6TyXV|Rd3kb~}GPOGb|dJUI<;MJ9zQpN#V zN``BJxCV*dXR1P!Vd9oi`q{K~FQSfmV02IfJ6bL zB>wawY|%`88O)XpOHEb>_C&lo!0F51C@WVHCj6F|RQ*{6+hj*8NX1N9W_8CuHE#Qs zx9xkP)~PSWXgrqCu4-&osb)9}FG+)#eE{|h#c6}cgxt+#K>M_iJc0y?%V0@rm`NKn zPTW}6TB@D~T--$FU0RRDD?gfHlyBp8vZtuG)ZTccSjL?5KrpH}qANyi)jmpr0IG>9 zXXsxZfy1r!o}em$p+!+Q=+?i3GqLrn^l7j4cT z(bA7NTL)*FL-5B`$oLkpGR0&?-IMQ9PR^Z%xV3%8ysRg>_5B|L;MN&Qs-W`-d}cOo z0>eiQYLR1wCUnfqUGY9ku4T-v1|oxl6Ir+i-+_r3iinG?*tX2y>+Y>Ci^}!tFyl#1 zSKV{|uP*Nfx3#)yNhdfCQRh{HHmDrjE?d>a&qSLwExz*c00Y&msI+OA&%QqdcF=F{ z=i>*R(IgRnngA@y9FEG`;Y}d4oj@hy{RrRx-VS?Xp5CNhYICW7{T48NqQ*#fY+9x8 zeSdQUqjNQ5R2!l(@2Hu~z@@_(m%6+52Y93X0-}^PgvQ5|MXShv5p&zod zOS!8^@^Xbd+f=q2PcVwTCRY(NeT+&OaxFIomPr5z}sl^uRV z<%1~cgQ6VGm|me?tYHB($YByxkz!)YSCOjV!g3TDLTH)!+j7j(TmN^xRZNN%lSY5L zmxEUxH^9+Mk6<=}G2bIjw7q$`7t2`DI9nlV4YBWO0d%D-oEKRWH3%~6)LE*PCKiPv zpzENateP|l{U;GkcoFS}Kh)~4S;Ev{*6ZBk%T^PM?Oa^d-qice?@GeqyeMZt3(Chh=B0_aO%~{=UiAxA|99zlUG<;0Cw{(Hvj*7Av0mV2kvMlHx@V zr&W8MHJthHb6|x~W$3)WJwTt6QQXVTh?89C3KF~Y*jB{yYTcW-u;H82QUnUC;7L2^dE7Czxh$t zzmEI=#gG1z+xu_%(f^7!m^j)xI~bWb;xn`Sv(WQD`_aE~iT{g!^lzx)|J{!=GPC_l zLOM}>-Ddx<-pxOOhsaiM6IZ%eFfLp=)|FKZw?=WlRqjz#6DFgv5Q(V6YjIxolJbm1 z<1x^HAELw^?d9!f3uPAH4-;x6e_Fj?t?uTnRG~;rCnPEjX^6jW1EZSjn{JwFB2gL^ z3mF;1$4_FvJlnIB702;S*%BzS6OkH@$6EHvDN3B}=NtJjZ%useyG|#3r@na8*4pDm zDH$Hy=LjqqI`Ba}R%*Q0zNhbt(|p?AsPhx|^1H10ST?g-+mUl{Q8V5}KW16v_EKaz z{BUrJmQ<((%`4jFt-z0GPq`I0WVKD2?((ZE)=*^jU4MVTG)#Ep4~^DJnK@QC3rP_D4PPA?wwmK62zBzci4LQT*SD^Ze1AY49k^#x)=0dPlO~@-5 zMUXohE1hl&y3GHq@G1`XzfH=Prm@h^tKJ4pAqg&Q!>w%^P$>hH&6#xu-y|2gw8LML zCdb#IJtuUPSSH!~xwGT782WWsm+8^TjQyE2loJe$jvat-m~(j5s36EAJK?u1G0S%a zuO5!o4~vqIw>1=wkfE0?c^DUIyi4jkWY8XjZdGm0=Jz#PLNsYymYs_f0Y|<11b9js z1Ha7)3VFH{H}CV%_TeuIBTXfg~(NBOEJ)W(3 zq=%2paJwwXo#<}SyA(h-nP2&k?*alslx5>5!0U+LmlUtD^icqwq9txN?_6FL*5Tt1 z?K1H^y}ZZ|h5|oBK>|UOwwwWRm1Iq29MJAmGdtrabjfn=Gqhdb?B%?=MzxA61+8JE7e*&yNSA2@pddPVQ0*J%6p|7>{H`VK-A~4g=bs?v<=kE zogVtUA7lk`4`Hi#p9baAbRj;nZ&ITQc6)b4I~ybo7+KhM_>lUI7qA^oN1ThdI77}S zh=EAgVFP!sy@-gAd=K3#JV&hgx<{OU8=S;i0#PC_-7n!v(3pFP+*MG>6tnkAwOrVr zMJln9iwSOXd76~AEVsn5h|0+1q&>?j)}p`eN#}JWNJe>pils>MyoWX`|5VS-W%5ty z5Z>JaW}|Iva^{Ee%jKkyaI{}Y(gOCQ;fDpsXi?UNY_Xs%fwYVkceq>N&9W|G4A`lu z-N+)O2R?Y@(&9XOj4W>)!;>5KBtlz>-w#wnn-%PHzNl&+=x?=DG}~q?j@Y9}qbn?8 z$3{TBY?XHkjL+>vty>r5|NyR z`5A=?BnORgqiHK`!wfQ}3dK zJOlk+%VCjAjm@Dkc2j8bcod2hTpczV%x_Ti@FXpyuv!u5XE?G2?}d>w*QSKW2e7E9 z-3(JBLg)dJ8hm>&^N`&D=X+RaBd!I%tJt;ZJhzfL!GmQFY(S*!o=? zWzV$lqj+zc41HyJS1|*M-dtCbC{w$)okl_Vo%){BT&9B{ns@g1F~@N9ovoNvRNEN5 z%9U_H=9b(HK}}Tj$y%qwK{z!Sw4GPjo`KIr6HrhU!&f2RBLtt>Lt_|O zJ^FKc{(7aGFj2KOVnE(8Ck!>66H6ew-Zw!yEy#&_#RIR6mP;x0Oq`;*+kob`Us&Z7 zmfpG4%nLi0y^=iQW4Hi-{}NyV{fn%+Op4v@f^;$xNI%eL3?QlK232K|yB`R%^ZSkF zK(}8D7@!#Di7jugSEpe>dGDD;V>HRJz+2Nzy&`LwD_HiS^F9!&9HjnC0Dwm&pE~Jg zs&T&=Ye({vgE}^-Po>sRs!t1^)8@LZdGF4PfsTnLFINns56_9U?hfkn0i*Lk6QurA z6W-R_yPX}e^JpC<7Exwzi_I0+XUlLcH?rEb0{Sf{-GTwE&!btEa$wh>O&jM{Xt(zk zppvlNfm_C#e8SK@WNkB=-FNW*ZzO#H-9Cc-e=BqU7Ww!GG{gE=f#JW%+<$T||3fnO zuiO9UtP9KEIG+DSnfo_1=Re3?b|&V3$-4ZP%zgexu2*=YyP=IAm)p{lp-NXAr1v}fYMPQF31R+qH7L6=wL8}N#AXX- z&x2|_jE=V&b<>NrGH2XZ_S=KCuDCqPda!UQ2^I#Yoqc~GOmfQj>o(7ttVh=uHR_Mj z?YQP``V4ICM$B1?I37{`SZa~mJ3h9VO-9-juc{~pFRJp&BO+3iY)~9mmI>9oO(4ih ztUN1?Pn`2-VYc7#!vB_iI_=TLD2eN5tX(x-3Vm>q$vypBn;-l$1<>tXAI@fqsxN_X1|B z(@seUQKvcSZFSU;1-wNmqRW;nqD*L+CWys+c6MtTYI)(bIlC=@VgNG9SV1ha96gAj z`bZVD>WzCsUlVc)i=ypLHg?H@fLYN%Bdp6)YkFQ2tLBWCrG{gkDp}T7K%0JmS-(Ga z*s#|p_WHieWH+`iX@s=5=eRReFlWF{>xhPA{J> zYw6=5j~IQ%mI!gO{>@fvxW|rVy@!4o(l!OhdC7!%F zAuN<1z!wyV=JZ=!;W_2am~L=j5=2RM$UeVUm-jr3TzW@pT^E~TpbkP|Wzll3uSUK6 z<3ZqO2|vfc3I`8S5m13`RAg2z80)O5h*yLj7zEY5nKH^<98X+;MWTQ9hfGw zLG9yaqa-zMS7zOAvJF29fy<0E7l%l+>dTW#JVd^3w}_);U|ixk zKIf7dG_ENE_aOQOYbr|v6kh#QCAzKhHQM4-rAL7zf1=2^ z#OIfdhI?2E^>pBp6;b?Zt;Ur zdT~{-ZRgWrfSDJ3+_oyKxHm4+OA93xF)zA0iST)*oY6GVbXx#9s$7&=_6>%}j_djg z@oHM>OJ%KmnKKPM3&dm%8V4Xv3BkZmnjiC)^wQzPy(7XW5qR*sk-7HCRlkJjKnxCX zw+l8InITj_Xbf^Hov;PyfZ+TLU!Em*%RkB}kxUgpBZpu~EVL-VzQHGC{DIw8iJzsf zOy@b@B3xm&urlBXlvFFC^P_lK!M~pD!ul8WlA{KP9yOsnrJtLzX267Yb6QD;`T7B*>X{6 z^+4brb|&Q9sLcpsvazhX<&8c6fS7Q4o?JZoj?U3hVUiAW==HIAg+=_37B{odcMiUT zWaqaMo)Eq8HyXM$_c5;>DTFPX2C-%q+m^P@s8zXEylo`ki|8I?$zfJ37F`<*n#W&G zm36e8oTl|PiQ6PhcQG? zK~1>-#2V(F4`TKdaaB8x|rvogGTz7GQDZ|9l8dGo3k#4>b` zuWPztoOe_jD~TNo^f6Ns6+$s;P3HHMBfhOTG$HE;r7 z{-j!%&^d-?py(y_5@QU9zi=&ugdg>gF_U0C?6=%mqeuh!8Y`Cqb6euTN&-0~8w@;1 zd|w|cCwlGN#a>4g8f559JZDgc?2QXgOm2GmdzGbujoMNFw@dkA|SIXej^iS#GYG111e`xt8p6d zP#h0t8*w+0L-fZ)$aUYggl}h7ItF{6;8~cEN>0}6Sy^{$5UE_w&P4F|5pke>H1qaW zTeK0RjRS`~Mu*whY9gcBDEHksG!q9%*YyL;i(dYyjyP`l`C^6)J4y`};#_umajPopA-Qwiz;O7SUEsF3Z3cp2mS{o>&_Urtiof=8)*a zg$-|yR=-m^fGZ=D;BFa3G{5k`S0y7k~wYoLA%!mhj#86QFXEU90UA@sbw0dip_rAoONMlm{HGMxuUC=(3VLOQD64!MVR{?$M&c- z=e`=d_w>LB()wJIQWT;gN3+ha;NY>ij9x8A%LU=stzp^(!9`B8HM_3(!?wR{znGu` zmn$pz{B6@@Jhsau!fX53nq04ncMOZeV4I_wf$3dogr%Pvn=5;%%BQOuc1-CiUHbEq zayM>)EJZ~K!%&WHnK>~l8to7qt$&tXEeJmmTWk+IA~6Ly#Ma^ZA1&$YteD#W&Qh@c zgWUT2$@yPl`M+BV)_=lR|1*|?_5Z^n*uSp%UnjZ#`mFzY%KzO`Ffp*R{M}M4Xl&bV zjKcUl|6%Xv2r4r4FeN~${TyY(ky9oJZu3B{-taw}o>vIMnShlrGJqMP2|S61hP--gf2vtO42Jy-HsVp!^6|4B`-RR$q1Ks`kzT8YraLj( zrFKiV7YY`YR!6MlJ-{7iH8p$Md6o*bfwX2;lQXKo)m0rW0_KPY28$yO5zr{FWcuu# ziPQH|B4ZqP5)v+(^$0QStVS8`Jrp?hVkN$HtdcCr%7^F6O%rkHJm2uXRodW@-+uAkC4l)DlSd3B0KX^^Zv` z`$PUO*`b^Zp=0+E)a(mt2vWIz|HrK)$_rb+4mx-YyVQn1OH1)UXZJeY;(EPAlF!6Z z_Keu>%e5P84IxsvTGdK&jD&31Vi4eWVcyy@n8W4ZeQ~0~H4z^XJSB&;q6V?d4$z}w zr7XN|+lcWBsm=N)i|NZleA-v13_?2#!0I$D&v~x z%2J$+2?CX=9(*zPLS4Me)xe~s+_7p~8*Hm{t4|QN zkGpGOQIcq$q zc*E?oq-8ZWaT;}E#1@4=T6o*Y66-wz#$Ib#5oA-&N+kR9#1;2(Ls1@e&;T)cT@7uyaWG3-ItYReg>*em|27}JjlU%S)OqgIa~%mx zol(Id7%^HPen_2D6mtPdAwt+%F-b6^8w2TXCuNW`|Jo1)>#+a6QF`rOwh&yLU6Sv0PgtoaX_0VV_?^!HN@0tPx&xm>J$R zH^9VnVc%_?iai4*l5-f&_i1_?cY;h_eKe{2H#Y>c`B8rkSZ`qdC$4YD-rLjtZfTw! z!NM<7JjU(NWGrA*m`SJU9|^i$6QdVvtd%fr__4 zq`eH;V9?uJJNorFQTe%s>nwzwTSKqKU8pB*J>NR){B zj=JR%DX2au?=%A5_zTVsYs;-LD@SNig1(A#8DE+WkN9Io(FMNtLK_H+ng`-TLx(Fu zrwvLT9rnO2K`4g`DJ-(82+tfl)Kzpe9id0ODw?1jp;bptO8yQW_7dt~bPT=j? zk|f*f8=SGT3ONjpe>~)s<1SO?5NV&eQ1(2GF2u|y2xDokoOLJhP;je9`zoE(Y~8{r zh~aGVp=jkh{#}Mwx4(B3tXx$zx}|(KBepQb8(WX($ng0p+e+RF;URQLif>DGlz=}u zNt8ylH~RZ(@YP*A+8biR|A(ZV@i+1L{=Jv-Kox6WS(u*?u6zw*>HcJi`aJKocaS8( zlXHhY9@UY|oGv7RSuL7*&a8FuX6{G&LyCrN(|I0j(pu;tepBRR6lIss8o~BM43-Uh zd@D8b#5gvUXziEoXuH)8!#Vq(84U4_R0S*cAWlMB^L$`?=cNcrCF8|BWyU)i5PQ59S_AhvYc}Lsg zl&wZ4+pC5(0oQI_Ikhg#GbYS0{1(Wd;VH!`dYz{PZJJz&?F3%Nq;^YYi&vbw=P1Vx zt&CKoDEE=JT_FfL8)GY~AkEaqw&WZ$gx983 z1cR-?2G2A!)E)R5C>{vTCqMmcP)7<5vFJAueD?f_y>oO~ngP}0OlwAmrl`uHaH>l% z+#;sQWx@!d-(~-Yy0;3BtIN`~MHYj_vY44M#mvmi%*@OdGcz+YS{5@iSj@~U|0-9< zA78~(clFFvUrgR)L`FuOeezu7e%}48wM>D}F=IoD(L73`op}#95K#fQZ#zuzVM<3? zb1JjF;O82GU&@PZFr-2C>o;v?qTMmM)Os`-8`*dol_PzF9yr#sJ#w60x_?22qYh@G zBajw7kVL-Y$w>T0M(M~>p<%F;{+&|1`H*o6b9(_wh3^Hcz$e-*$$T5p{TtLuAzf08 zxz<3SpNHMY>_Htqq)RWHXe#mIsYYi#N~0UoU}$QtCTqWKvn)qRiu((}bw&_cWp>~d z{Rc>UCRI3FOni{CFTM+?) zYFVHR4lD;ur0!`~Bxn#`Tn`e2Mc1p8y-ZjRx-14sX3c%eDhKLw0jx^pO%|Z(v;Un- zsq{oOE5(%Pws@h{ zO;``2>yKQtCwK#yr}zLZ(g4#0d(eeZI277qkZO`!8PaX-G0W;CE(pt5GQH-oS+HfA zi8n%tLo(lI8p~`xFByCmr0;s}cC`K?uFRGmv?}o)l07E|cL+*kQ9Qep!l-FB>IASF)jHE8w3%%Ysq#I-4v zIF&wlz7pOZo&U<119cspoCS{TE5WcOXCY7?8r%*XKDTS+aKMS9{*m*wz1oxUCq#M1 zc?)UdeF79Bg&q&Eu5+a@VKw(izEGqsw|glmt$a&yo(!AG^=;O%n;7xO6_{5di*~Nz zq$ojq^Sq5om27govc)>J2=eK7&k(_UiXZ)V3eE6C)dM5WsZ;Mptwn;q-uBS7ORDHY zL9!FN+R_74K8B_}rk;AKQ#c%q$86C!n3U|g+EQJQ+XIYJad%Pro5i-}53QIl=@zmd znKUNUQ=v2dIM^zYt{XZJK6kpG#0L0*(DzS??Jp%Le-45Em`(pcY=762{!PU8-7^)E)%e@<+S>tm;qGV`5MsmR&jvt342xv;sk)Nhw1(;@{m0B6RuAW1QTsqTKsc_$5Nccg;X zQ4Z@sA+y5|Eo##VpSF$f21t9M6PY?K9XmO5KeD8)v{hsx#Em78Es2T`8@rBM*xX-z zJ1y5n@N{`1G$`!5J9T`lI@*T& zDy-E-d2BrD`JXVxzCKk-P>9wa8~F>}{yY-Pm|=%EP5n6S_i94wRw&v(PZS#rcb7b! zGpBV4wl7MVXh(f5=}k%MBuZGQr-60)Xz-}yKCS8(N@?mH9HCz|9!u4m)tSpMCJV<$ z?+_4OtxHwA0pYpkDg0&{Z;;#0PV6deH0#5eZS1%KjaDgL*2D?P+QnZv0ls28z}R*wPF+`Ywz?1?c$wkVYR*Oo zp+l~{Z&_a>Py6r?CAep-+eH&8fZ|K)-1QdmqLOIfF&FOMVB5dp(h~Zbc~;;F(;1g9HsDRc8%k`^2t|m zYqR>hT56#U%qDM1R)6sT8OJ3 z1dctNUQf*Z`O&hqCZWwcYcu`HSu{LZg7^l+Z3Qh8b)3t5l;2F7wQI1b{jb~^${K^n z>Zv3zfz+3KD|qA~0VWg+PSU`QHe~7w=Gh$^a5hWg8m>!ZumR|0LF=X|x43>H%HQO{ z;eXr$L%K&utYNcfkUo>9onewD?8Im4@4whA+^E#eQ*!95m31az#ft|wCi$y=g}|gV z7mX{L4HbQ{f5$RO!w}yI6=n!~5}@e%K|#vlZYR)2+8$DLh|V?dw%q55qB%BUCETIz z&THF&!h`i9H%7)U+o_yzXeBO{TOfaiFY$Z|PC9o3PrpM64VX1ph|!<3rI%iV{0mAI!(JOPs>@RC?N=soRfZWIikb#a|zkMV&N(2<-bS zE&5m1gB7S-t^B1{Fd4Aw3FyNfxc+db#;}vut%v7KLYJ&K=&&qwAfjNNtgc2nS^QUxUiud9g zX^g8Aes|06WBJ#Qvo{e!6RXOCB=*Q9ZC2|x`v)gP%iKAV+F2y({(1zz;y%lw;yA&g z6g$M@xs{y7NP0eJr#LP2PQc^A_mS5=rvoX-8cWaT&QPBe{a6;SV+lPS(rcma?Q0g67J9C0rL2t$pb6LcZ)$Yp!62l!g9B>Efwci z!)F|*<_5j4@#i?8|GDVw&HPg>SHjC$;7$}7TRG(#tlyx>Z5r9A;79%;(Xo6ILpY}S zisX?hxTP6+4HwQloo$53MWJ_JDzeV;dO#$FLvD!86^Q@IGD3R9y{UsB4f-BL&YK?) zo@ZV;(Q8l6i(fm=R!TKZU4BHMv}rocNo}ra?ht)&%7HoH4588w-VpP zUuem@m@>KvadG0jLSWR#_t+V;;N4|9e8uj9mzzH8w{59Z)>-!Hrn!*Y*bydM8M?O( zn~wLBO%;6oF*_!&Bo6V%>>MCCuM{suE;_fMoh53|nPeZhsF9{7U_C{^{L5HWK?#jR z$Ytg@Q#H8(&`-YFMG1f) zYCm_IaSk;dG^)SALU{)I$fUenHt_>`IQ>j+6e`6rUxqsj%K=1Qr%#`FIDT6e*6{T- za!W6v%k03BRbUNOiLnhaPZQXxJniTjRg_X*d+f}B$@bP7B5aBvGTk&6FE`*BDlkY{ zALU1OYycE1!54YLM)kMc?Y(XI;!vi_DHPClgR%-7IFntBgf z@%wnCA6pfXQzdP?=Hdj_&wRSZ?_U0w=&9IAUM;K~gM5kI64FP;tyPLKi2yU=&3)sh z+iRmVoMjJR!GJfSS^~aCFq5DN{6s1DUuf_uBjOkVpBBQlyT#GfZ!x$=&!YFValaFJ zx#JdZ1Em$+oK>NBznbyZ=8m;Hf~3kIk`nsIP2!|7|8RV!g3~SnJOco65~91DaYkL?2O&x@WTvz38YP|Ij#@14awsD_6vm5g-@in1iK?KYR*=DZs% z4$(6{Roj}06QBG6{NCM@{5-!N$hHhb$(lh)7;{I2AZi}V%}iP?xOs9yM#mN zwc2#m_Yqf0ow;)<90VVBr6^eD6ZvCedIq~|(SX#Di1V{#AUtAhIcCZCg>!Idg$820 zQmZ`cAH~7vZ?Opr03;8udG0trAwkVNJ3&lq$@5j34Ow9%B|mT8y~Q>Hk)L1EIQl}Q zjGkBz!$B#Bt(jzh0(Qrei+44XJ4`zc;v?k>Qvqduf}Kwv`Ns}p(ww^N0Cvk@_@E)) zVdhZ%*MtqC1^o8H+m}-RW_DPND;AakYu7yw?)Le)mD{6SYCRTLIij53bjPu(xFg>- zIYDB+n$8qzvP~t%OJzF(XARxDklz!o9(Ne+ z&pg>Rr{)($ojZ7}iw%FVpx^Uu*++k3*{9LP3fs$r>0^Sa*p?Fdyfqk#_l=aUg{=L! zV1G4h_1sKL)xUi(WzaG8c^K#L_~AFA9?+2|*Az8dHI)Egf;k1!>9cNX7Fy!^pvyxUxz#)Y|}^ z$QUE}K^9$;{_TC?e7-@E3W4`oHCfSDfE!ENEc(>JW5U#%SBF`684akZXl)Ar{%;%(dy}YI< z36@VE+TRiN2d!icTzR19q6%`+%PbVdA#Y_4LrE>v3m>P53Db0B31Z^T7MK?@neMjQF+i+fx;)v;_7o-RIv?LMJg zZxZZAW7c=l$BY1TJRo;H50k-g3~)uNa3nX4{GZ&kaGe{mP(w8~S4hay+pGz)w=3-jX_umO^q}{S5Z&yV-7w zn)3JU^A(30ztk5-q#Dc2p2ZXcGTYU<5)>DK$$5rdsRYvNvMDy_bcbzIqCRr(4n zBTfm^(}U)$JH*-JPQxO2S3k>6s?UgS42kHG{muE;-Q(KElEDXpxN7YUe`g_tMhJV< z85I(pyg8D26gxstPV}&5J6TXdbf0WJ(F;;bDBAy;1>v=Nn48<k zehte<5?m>A&|uDx-&KbXU6ej>8x0Rs4=_(0)e>an8X;r;9u1xE@zv)@xeR?rNSI8H znIqf3$vg1_88v3Y_uE{s(V2U@9$xZ(f-#ehifnQfCe7(l7?ATo_V8{S2M%XmJu>*K z5q|Ux&ycJP5}>OyMv?FIBdSuetq(7~pFqkQz zX~ek;pmW>6tY*AQnKeXN%*%_NG|v)1ro0o@M3K5|8_#A3RNZYy4#W#>Z<+!{SJoN= zQrW$`6?!C!QdtUBg$i?&!-G?@B`m#y;uC~V1A2-5sQhGi#V;_yDftW+<(Iy$Vk?m& zpkolcn1mKmrt6j(Tjh#J%xf72#w6ebOI&>oVB!3IccC40j6{BYY1AT1GV((X0bMt| zpxjgJcDG#dLe!XFw2Xqkl^BjXaB#&xkyP|5PlOWg%{E@g#)A~+KFSmszl(Igu8`|@ zmwxK#drpWyFn?p{;~QGV<(G;1B^u?P7hd1 zl!n}R=9$`dQRHN=2U1tNJ9Ncw?RoV+N818qy1pd>Oo@(Otg2;RKU`eJ_ZEe|P?>Qk z$pd>U^>`C*k4F|$VvrlVFrYn6=N3Nn^{{0KljhyaqZ@FqG~4G(F;Sa^_QIXTS3+2X zvrZK7)Mo*fHmcOq9Sut=cHWeP^gpsq_Lq&#PZ{BdqHULspY5zxfK7%=6We5WrqQyB zCm`@PQ;_0(DE*~ic`Z=hmGVdD7BSII7jbI|#)JYe0Op`^9TIR-0PpZ}SCh50HsVDpT!SL2M`lQIyaE zV1B2MI1qxySL3ppDWqJ37tsR+q1(s-vqRCXf6mi_;g3KwED`!P^H}GM&KKK5sfI}l z&~SMeFz&glwGvZ^PG+e7;e^TVqraj;*KYETpcPT8iN($I6qUQ~c*@aE%8eP!@xWb0 z${a=i^ z{a=bW+5Q`2ZvTAee_TcRb6fvXMPX!T`Ntwo^)(wT(LYnGcE@`&@4QVw_V}ACdpg3p zV!!DDd*Yed8#&U1hlj-P|JZaa?+7g2`}gb2_`P&Vlybu&Yx8MUdX8LT(eO9k zM)89mI`DmGIi{CNHBB7q-a79*k-GCMWiQ?hon6@Tc)NB5K3&>0_ATd4P13r~O|}N8 z`-Ey{3BiLb-ejc3vb5!kN5!bO%$387scMz#wiYMH6jJ>h~S_ZkDgOhV0*wB}9A z-jWn#Z7n3v(N6iTe=IpIIp3_xtrb`KsJwLB3b(5;&D~+fC)he^W*XMlvZ2d;6We2lKxOG-+9(pAhB*Y`Ysf4|L?jk)H12Q`)f6-&o1=f{EPi?$~c| zd{13sdaH1mY*=;uqGlqXl9H)PC;@ERm($YM>YdlD3*M>_dvEOwCFUGeMr(=hhFzON zx#ge(w0VMo6A%MKuG--cIJvzd!P7Il%fSefo0At%bENYG^>`at1Ey+DH=Tr5a}>b9 z?psP>tlhk)i=LCFWzACRwTI^GL2Z>V)IHBc`(aOwHfec?cuCr3sxt4pRitKR$6m5& zyErm*n2{cbm=k5u^_0!kTO=Ey@%2Hu%9gH$MOs^1x7ZL}jSLx|=;fHnf;h58=>#6((AT z*uWUr%6#gCumSg*2omUEzY?SZ2QnhAMD{%209|@Z&B^ zw=WJH&(0rg9@9?mI_0pCDFo|KSY-76wU|J4IUm5q-5(CTjAu(x0BXq!MAR>*% zzRKN5T{0F+eh={NUij@}f7&^J{x`OQ1v}S&@QKK2U z%~)WOHmaU!s{q4PDo|1tis^m~k}lEIeA>KNd-drk6(r<&vd932c*kik=I*@KgXDV3 zwIotv}8AhP;GHdMh~dD^*&-YSfW%i zHr2XLwVb=&1kc;8n1U=@|1vozpSN#UcXR+9xH^mW{_#=7IDVhqx>&Z80K8rMCVhBN zYORS80Z1Paw~s$;=xhNIpFSWnk&qQ3#U#>-PSg)nDU%KAtmBn>Jb^RFg%*PJW>ePPV>#j#zQ=*P6i3t~B{M(Ur{ z#YjopWdn@H+sq(`TZ###H9?#1)BmKl7}BzvY!xrw6r4Y<_Dx4+=6?<~I}vy|b>q$~ z8B;;8coWa+Ax{_uVbaUc>i+7kx7h3mtxoBS2hxMuk*agYj0`LN#R1r#K?PHNSAoP1 zvT>OWl$OPuW0$z4SvvMtA1nQutZFa?X@?2>JzVR_1XS>I^^Lk&p`2`p6oJT~252Rl z2^}@^ugD3XG+*_ouxd3>A}1V&2CF6l_KA*0Nx@TmI&J@l{sAXnzDg(3rJmn!zFyq0%YR-TV}V zXCFr@v*VTfL;fOAffD(FTwU-$_d@k=s?f8!zutHeNU;J{fSE!?A<~*7ET!|~VwB6o z7+LA{SE#46W1Q{dz%~F_xbZnL;-hs+uJyd-9ag4X`c!)2lU~U&y}$cJtwE`Sj(v2& zlB>P5VeSYm_X;;-!yqH~kQ8Ro()Nuk3|L2$W{b-9LcaYBLGOxl(r(L-w_`iGT5mS7 z`BfadDfa4>)LmK41Ihyi!dDT_%JOW~DZ|JfVUp-1&CEj%Ikte*;P$y|G>(RD;5v47MH97UkcE zPh?)uAffHRj;{b=0Xt|dAio8UU%4eDY8v#hZ7xDc8eo?%3O1G3-;xP26F9r}=s%l) zUK+=8a3@)|I~l2JmPo?yO^tS!DV=Zf5ju05pKpaMeUY}dLpZw{Ap5yr?yiM3kvm~Y z7ZyFEqT^>IFyj#dB=6XK!!bUY@DkNULnk*~Z$~ zs%i!O9K5rH>o(CKE}UHk=jGQA3DdRW)9J=IO#}L(iculbDd+&mhp!50g_hpScO%+o z$So~IhQT2v!e25myN1YZAH53iyJPrRdTiZ8$(cHj9h9d}(9t};E_L{FJp&9RZg-@z z6QW*7SomtDCVyp}H{CxAM<9|jH5IwF;~~Qa`YI=QUZVACr8JRUu28Zm!G1I&rif`Od+DzWSRO`^A+DO?agPN^@ilQ?_^Ix0ne>^ZYw78Hfw{9qQVR zuEiFh$39Ej%-?oEa)h&MK3^z_J9)`)TCDn}kEioj>HB zAmok~GT4JyruM9^mA%QB7}gu*Btd{^j=)-%Yg_6xfMY4{6Zs+?(89Gv*D_^x7ox^< zhd5iNv6da1VrY8nM3n&=oPWYP3?qe3)ymci{cZ(14ke*VA(U*mi;=4&{33mh2Z!B)oJ?eN0Z(;qQkl?Xlm1c1+mX*lCmW6?2rM<~1PAM3D6s zh(>&RmuEje6ITsyC$ydj@OSK-YRI29FYHcAr3+T0w?DnLXX`DA(r(L~@lhYl#@Qgo z5+gD0o<{={b^?0PdG|rdpUadtE~-4V&xTuGs(o)3>(|pwQvy9*R)S4aq+iz=J8}<` zJMc8U(fV6cpaA+HGMJQ$Ci%pBEWz0nl|v)dDyVK@CJM}+YyJf z4|}?f`TG7hjA?Na&-rHa{8vmJUnp5Hb#G22=kxs{BK|kD?T&(pF-k))ee>IFXG349(FR)|3m+J;wV{3 zPzIF#%V!ivDR}pZ?*6y7=7j*cL>2*luJ0MuFgB`~5xScj$q={TAd|cMj{%Ws5jkV7XwR~pBhBRAqVmymwm(fU zhhh{<8p)F7d}L0ioXUl}4n^~<^UW|r;H9vUiEPnP=)}5G?F?}ji;fN-phhsPLVcD~ zUV9hZfq9SN(<78~( z^w}2&XkAhwdv}!*DYKxYpz3ZUnV_#PpH3X!P|kSha*r@qQ@)I{g+C$LU=m{f zh9#xf=^&q(y3Wxs*sw|9I&83>Cx){D%zX4YoGC2`?Lx&@wG0pkJxP|f6(LJ4j_G9D z<}HPeV6&>d_hB6XL$~o=gqAV5!x#% zm#69;fzV58iNI`^@gJmK=*ySB2%YUclm<~Y=ow8BR$7cit$Oj#6#?od2iB=8aPnJ!ZJ^3dbV{g9i9xt>p33*k*rw82Dn(H;12g zAAXm_-_4l&x?}e!0urkftubNI0RC<+>Pmbnb@edZo)bpB7uRmb_S%H2^M&A~i!F29 zlZCZkIX|mdL(F9V^28hKw!^P%4Rg{B` zOUm&jy=aY~AIIxbMv<5CP6+{LX+~OK@T5|cbG2<-rb%#nDv^a|iW$KC5l3B$0!3K! zQ@QnqEb&zg9p9iATk5+qzPpRvQh|MgXyS?7z_BietbsM%uqggH-*1DPs`LDdl0Xsk zOr8EG#kSObX$bUO+M8{A(WikzfTl6bMkmU(^|<#M1FT_gB({jGi6$~66EmO4t% zc>7ZhutRGNZ;Xj%+77XsfccxOO!%z>Sp0~o^l7a)F(|~S z4{Y`KpM{dnC`be8*UM3bU#BnCm}JP@#>4{PUq;qv7rCCOpO__jncIbbB$|FtU{2d6 z7S*_GFwq%YWkgUT%OGMU^#@hrIY0c;dG65iD0{oQf-3z=N4Yu4GgmfsS6(!sZF^#F z5mOQ-w;ZkL?RoUoG*}NaNjWZp*N|HyKR8rMx}DYQS_@+$wJS1htiM;ROb^k;aBFy3 zK*+r(Yh4UY5mqi%@Wev<+g3GDplR@wD@d);0hz8{5>qwffbu{qp{XGSN)1HW%+l+V&yVuMwv4bEMr6uHuq-&R18aN=fDv?eH*>aUw3H_DrCC{?7ehh8 z=@m>H;Z4WF!ylQ8NqCB9&K2TU2*9O)96~xEGJO~0Qn1NQ>pfVos$-oRFt9GBZ7tZM zC=F`NLmKW^!4^3pBbnPv82=`!k*vv2N>M@1J?get^ZFg}W+la#w+6%g*Co;M4I?D5 zxDX;AWODTbFs2%O(SUfZnpYZ8i+84q8r|~S4>q45)Zt2)vPV`}-NN2@p<%0)pb7CRA2Y~`onZhbV-!xPdjUKGpRkUbBTEBQt3#?Pyh3M$C|HLC0bPIduj5}ZG7p`d3oK&5_X;KzultbKElx?tl6iY& zQ~^O0hQGCCPDLbi2P!9aihjXG^yT$}RPV^dMiYaV*J0B{Y(3zQw;+0gx#75Fu6bl; zLCx+5pHNNw05s`VFnwEYx6=D{cWUiPyxSEQ7k&5rYSD9u5Pid|&w0SA3UkS)SSux7 zXs105gUGJNw4IiOKJx1g#Wz#>%=wKp-9UO_iXC!WUq@u5RG$wP*rr|pO$Ra~>MzzH zr?3!ZF6?~t@cPp?$|!jV3wEV(E2>Qevd}_xu2?g0h_z63=?p_ZwU7l7S zUpYAzg0d^h$$fK??YpE_891-@rye`o6`f+yy11beggtS|9MZ@=qGba&LzuHO9A4VSemUwlOGXZ1}gz4q;@oR_F_BsApHE7e; zuxdf>p$k9AC`!0(P>?W~$KWmZ!u(tkP0r}^ZDiEkxlD=3dwE=9a+l0r+(WLa@8z)0 zmwoN;<^*pk+fMmdh%aT!^%M)IwsQG4obYuNx?~8A7}?1Z-n@}>9+-=FaKQHxMb?Gc zi`eD(h*RuJJe<`+lbhn0ytTuVL(xX0>CHd0_~h4-MkB*;yw4up@DeRY_Y%VaZ9T~? zt%bdDlt*c%PdSdl>Y8V^Mq)xt79)P!VvMgR#a`N4xuCsCNDvd-f5u;*}Xe~6YE zJQ|I&Zct`z?1pQ%u81g+DPP_&9fdTGoZRr}y)O${PI8TRpvR7~5m>~GxDa3QPI_PDJV&9=-`4QK;wT!B2CA+vg6iY;(=Q9UORRAo)IqQs z)c?7vD;XzJ9e+kbMWN|I1KKFlu5QGa)i}QV3$gwy1WoWl5J3s8bUS8eT``e_^^OYt<-}45W@rWNH;l>OkQ_)x)(x-j^Wdj&z<2r|F(k_3 zq0bpmRt>L`Cz@OC4^$j?xJEM7BR9t@XbxPt{s&3U)|wLTC$p%ChB8#V8(rh;Du zy8S`lz)Ax5K2uS0z?269iRFgux*T-dUBQ7);^dF@5X`QEmh464r9%}8o+E-*UJpp$ zyRRQd1YTvKSNIYrx=~1Pp9S1kq$rn(^6ih}L8MuM>k4hHz|0Qj*u)-4Zi$ZOgl&gKJc@J4 z{5zW9w{Tu#J>G4`^r{KXttS{tvkZ2sIDrO}6+p=s1!^H)FPK+0K}}_9r`Y$>Sw7LE6!9 zHTzXq?zLlL-x$|=ncZ>{;}x|6jCKMGDUpIpwIthcAd^#NjnIgUq1wE>~bX|L?f%YbjXf z1C9iR=3P?-lpwlszt?eYPUI50apJv`oSc!J6ca6B1&@$ZFfCr*UAdoyQx4}_s5Pc% zjL52VuBe1qM!ISoI^VFPx0+9?#>@{|5N(@S9AybUks)DUr!+a zF!sMdxxXBW3ffxPIw;!d8ya(Q(Fr;-u;a5Z{aN8BrvIN~-oF}HM<;ImnI;JS{Y_k( zPEFRp!r0L1a|zpl50Kl@TJ^Lol603D^!wUr%;wx8@DSip(~Mn zyvn%rg`Kd`>T1{acJ$0hn_jn3Ez&h1?cwzi3!g@SPB3l5BRhDgz1huW_Q6KIVK`Iq z`5IK#R;6mmB^=l0t@S?lG2f)vz`!fBFdsRnY5LHSfpw|d;;UVi&_5MU&34LlQ;^?} zt}}-@Q!hj-`SwHb?Lm?dnxkqVAu6P`$yVi)U&x2`0e|;4W=zl((($O z^|rpf=8cH0jcSf+p7}&Mx%Y5VQW_o_=|F!ceH~t*v3ZEeCreh1_Uy&tk3csZIL^KD z>H}Sl4I>yN1S1lMG`_&i2tsc>xg*8l)`D9jl5|Q*A-7cEDYeCsqrWCtT;pA;#flt{ zJ9v1A9bG-FY0oXl7TbiBZ8STxG-U8Zw}^9g54Ao+%Z8Dxc1`Snym|AR!) z%XL>cFGrJM(9v)XDmRO~pa`U|nB?04t&x$&{~x(eJode)`zu(ZI*#~Y6R?L z^35UxtiZ$UTf&LpBWB5B^jG`DtHd2U3uTU0T z{ESFZ&MM8~L}l6q7LR$PDx1mlx!@{EgK`T4XcVf7?&U#OdFz$osbSRc?07~tab4aSgf~&C68hm^nkiCzoN6^+%e^+tYg?T zH)6sz2AOYOW8g{+qE(DTCzR<7PBC)=y-eEgl*57&YcUE$TZE<=z)8Ij#wFxyvBH~s zdfvI&>=|y@aagclyA#z$@M*^(s>6e=ls}k}u`a_9eFU%{yl1!`(2wcv_B#Xx>k{`= z4LBm*XQ~b06D=9-kqK50p{+g;Lw1`#E|ZgfQ^Z*1>7@}^bK!hJLh1b_DAVXRC25b) za_WeqwXJ!y>%<>kfS*79#4I!Mv$1wI8g1ygVnp&8T*C^d4Gw&Kq#8%0Au4_`? zljAX7wHEdHtR~@@6RKc7X7;8qf+}PBI8Wa)_Yz3-eF5gY-!`Or73)Fc*VgciVz~*@ zE53&wvCJ^C9`G%B-a`FYt;Mz|mi7z(`h5K7W2cPV9ZQAIiVYGZ-m}+TfO}<@*=XQ3 zrDWfR2IdDT_=$kTxXs*5%-~7p)Z6!MSIA8vgBoNE2Bk?y@3?1(UqC8lp5?&fM%g5j zTRZ}WlZXb;WkTrCA5yH1%3&BHTfnu1;okOsm_vh`rFC3xTO7aBJi zh}YwJe6L-gzd;SM%V_|~fhvf&>lf*&&0_I}V#m6hU2DwGDqY+7-Sk3C*v>70Al)!l zV%P`y80=>Y16VndV}!!w83yOD%UkY^f@dL3e};8hLX5t zcoaV;iFCdxpw(3EaU#bJ$;mv|0#Q@?&|d|m{Af1@+K*F=`I^Xqez(K4FGIOQ6#SS0 zZz!y^U8D}NWv0`9DqTTEI&(L2G*GO{uAbx)OxB3m`3O`TbTh%QWMEYGgrri|(yfH4 zFTvwE;Ql#ix+cbrPSjM$^cJJrMvAp-^06QzdBCHoiTcIY0c`pa#G&XSq+ikpj8-;D zMf4Kigr~Vu@pQGiTaq5_h{X_)(@O6G`>zWtxZOuR()v0+Xv27F+$a>XDqWBYcq+Ty zJ%JQGHUz;)EmafAN47`9uBZrw$+`z+4=ca-taqZ%!GWM}RlzD0Re^DBdS&n10wKfN zb3wYXa#-$&UsA%!Lwof$Rdtt^q{%~txzp!V8gXu1!_gD9cK610c{_nh}-imO3Q=u+a!YQt=!3A;i1b76%RL30+R)`vD z3klxCw8Km`$de4fJwb7N36x!%CuqYoH$9)-gW>Np)Qyc}Szq7`^oV_VPv{S|i?q@( z4dU0VhUzZ_i?LF4%aj5yge>Y#n(2&o(vSktw$r}(z zRFdg;0rF>mFiPFRj0!GS+5D1LUJIiMDgnYjc9T3lmS-3V<(ChvjQmmb;`J;nMGK{G zz&qZE*-?&|V<=i^0GUE(KPV$bge#<_ga7S|(RI;D<^w1P>fsm7;Wwh#q|NTvtB>8P zl%$8XADit(jc8vYP4?AA99X>0@{fwzj7=e6=y~S^ZFKE#tcc06iiZlxeqxpXW>lW% zOvi)yL6`D^Q0Iy;X@7`zWaO@R3KQ$4&quy%RYAw5hgX?R#y?*ai3CacIo$L6^aeOn zOs_j80q>W%oFEL4A?g%~JiCLg{&Gv#WRprvU1+DsHoqST&L{GwNTVrLFAT| zX#t2#ovK-#9s)B=QjHx-&pUEGWEyr15_OejGiw&W6Q~f3K=ba2<1_R{IE`N6ThaxK zi~WS_H{$8&=td#QuGP!m>~eAwr=fY>y9*0^1g#HJ!o*~?m4QZVZ^!pe%~Rl*v#SM4LzAmn%R;M)Oc3#db2pi~ z2hKd_-)ziaIt$rMQ^ys7e-V+12*OcRz7|Co(9JiDrvls8@AA~Pi?wLU%7%r+_gt`7 z54km9VL|sic`|*musM7n7r+gw4)A$Kuk#5`{J~VeJMSDcPp9h`utBE4QU zCWlfXw6yJjFQ3jtMd8P4&2k^u^Fbz}a6oL;QK$cLrUktk6JGP>e3ll5z$ex+-~+T~ ztVY89i-+?PJ}{!%UO9e-+$y9)qN@#YZ)z8gjhI*C8*?gPn6_jfq;^y#4c+PPmY3b zpDz@KT%`1SclN#-6H5bxa`YUW&WR3=}6B!9{E3 z@;)HVn;?4xN@tagp~bcknLnyb9Yf(zzJ9Sx&e+HmHm~bBPUFiaP3}^{kRP6- zr;#`t zA&uYtsA2Co4kb!Ba=v$;cSol3Tko^v*5R?TCAF)Oir@(VVONX)%e)(aKd?t&q_&4f z5Q>uyxi*Ny1_PnAPD?}gRS{#+M0qq#PII3kW~--)SuO5lmN;Cd%!L0@sKAmL^;G|> z$MiIC+ves4hkHI6!h$%rX)+(VnnD1+T(Sk*q;CNskNQ!0#wx~nI_r9O`C#_>27`(M zhFKOqK)sgA&bK4k#hl9RsM}e`dC+d@NaMGvcee!@g@7e=D?sf`SkoF{b=YN(Tx_yz z!4%C;9bAF*!_k_J4dG*V(A_Uwx+O?d#k{F)+GSS>N-OtchdkMwXP1V%X~!eV<(eo8 zD@l9tG8={@Ul9^jZU)9k)$(8t(V3B30xNb_dx6HdG$1m+`Y3#iQ(=^22Zh$|=FQr+ z`30o+#yd6nm$u*)2)nE7Mf`5Cc}uSdOg_>e1tDp{MaIPJ<8VH8*MF9I2LEFUaadnf71Dxae77K8v0-GyA7xgdUODA(w z(pAdJHt33FU(*x&*@b!U0Uub1+u`!Bc)0j-%N!-(mRH2e4r?y4WpK#tLEf@soR~%5 zvB55lkE1FDfreY10pnSn9O#fFnS_G&*>)gHz%r;q+LyRTNKBw{;K*D1bhB(?=LG;W zLGx#RthYd|XS+U~*IT$vLbIHJoeV=$HdPKnHBha>7b@z_Zrem-`(HcHjC()W4?an&%2d z9BBfBLP`27Smbp&W1u~d&NPt4b2Nh zs{Qe5<|N3oue6YjM1Z57ZV^nfUl`Lq1N;!sh_ef%9U2rABztyck{z-p4A0*sFwahErz) z`L>~C-fS#{bheZ6;ui*)^_ylXt%jR0jBe9?c6<98FZXi1n!B9GH~Hog75%e+FW7n_ z`SWd`duqQf0&=^{J#k*_+$B5ti#)wupHT|Pkw1yK`H$4tNej7YLpmCYEB=rAer2NZ zPl=jra9yVmu@LlG9rRqnI0J3i7$w`80)14IJQN99^ifd&O`9hVT4{~Dh#Y~acOM$| zIiK+MqttQ5l&}L|qW`gG*XuDtrt}*JS&Qgpz7WZqLYDyRVsr2DjTeOq*offisvQc+ z%erJs?pmXRtBmh#@ZfCqt-OWos$XJ-;ra1kVoP96?_Ho}97_qO&S+g$hdhZf65&#k zl3XJCohlh>MwkQnsbR4Nuv#+;fM7QbHXG^ZfX{^}5cQ$$n@Hg-XKd87(Y-1v4bIy< zhXl6a8a13Mm%!qD{y*Q@kUz(|oZ8|}s|OOEy?7nTJcCZXox z*n;PVwlC<825yNLh30T!J3Cp(k{AO;Tv}>d#r@L+GW8$=%ppJj;;`c>V0=)HjMg4C zbeFb19SK7WF8Y*n{7wHJ@6)01vf&!}XF&|$FY{&jZES2mTfH#@{zM)4%z*#!DgFdB zf3k;v2x$JDy)OWN7d8INsgIXlZ@%sS{H!MH{Q=rBgud;q?#;n4jv) zms3xFmajz1pyGvw-WMhPl%Oi8cp(F%Xv!hmpvzJTp3mdH3QYb+TUIo#$;Z`B)kkThE zk3s5NBwv^OQzW+y%@T()1WegJ*=^LF4H|a}`x>mDwljeDU~?*#l!|uyd3H61cm`_K zuZ*z0*R7Y1qmhfPOx$@>1zgxn%)siEVJ-68?F6Y0%WAk}9#5o+0Joi)Qex=oj>H`v z@}pkVC}5|k!Lu_j#;u#Ugwg9(a$z#o`qw4CPtOE<-QzLPEHX8%sys&bwqx?BpLkE8 z52#!>e&>!>23g$`lVj8A_~HQVlN!(gy|ZS=EgIP?q{+~0ZKj?_y+q=xjLnNaBnLK# zg+-(v-Prm$GHp4^AWSUp6LC3S>Q#u^)X zdVT?oviJv$3s zPX8BrL5_)wmX-V7xrlT1p9QDh7)Zf2Uu_D29-jm992TSZrZ}^>brIk#tDP|z6-xpo zieeI6geZXUP7KzqI(1$vvC_;V1mli7%GH<5LedJ{XpvigOkx95+tmoYDuGeS=+@ur z`hK2L;tPua2!yl}PH#QjJe94T1uGJkAT6Z{^05M7&2->(@*9(o`A+t7^AzC|Fg=qw(`)CNyj!Q7)*f^vO=Sv~qxevH05^b{m4 zW}dc#<`Cy@G4jULN16kB?W1OO8Pkk#h=+xG7d}h17&3(BpR?K*BCcwQU440}n6ZRH zM{F5MNm%jRTZGfo;h~ijvt2MaTHf~)TV8u3po-Vw9s|AC=H@|YbEY*5K?ze)ghqSg zfhuSQzPMVK#}OxIjVZawLG#yPr((fO&}}mWJxm?w3IYp}5+dJ>zqA;HJi7ey`Sb#C zleHBJy9nM4*mWLx?RaT=Op!qp#}mh8P=DD1;d3=-t`@@)oij^3Gt07Hc<*kEIYv{n zAH`O~JL?ZT?ah*`5#NGF(PmP=YOZmjB6N;wc!(JztMZ~`YqjjgK|lRI{kf|@ehbyd zHP=zizaYJfOB`8U-0vZC3fC8D*%E&xasm_{@BU(?L>Nh66Uj$uolY%yk-LzPtFN~k zD|?5%vY+ByDdz_+Oh5d$p|}`^tiF(zgj{_heSW4~CSdmmW6W?zgCh9=B(F_f4CsjNr-fXeax!gxdA8Y8(G%-g$m>4%HiTePmV&opZeev4mygD zdSYCFgvch2uHrhD>&6INQpm*AF*x*-(dP4T0)KSGjBP zvUXhu9*Fhb#%xJ{<6$lG8LqL{a)>6Th!mkBGzl^eGziBChsTtk9^X%_beKGVw^rtX z-Xq7==Azn06D~JR6ThWGYNz7J0Une{MmFe`&IuDn{*2t+x0y#>4kRmR;C-OIW{ z+_ev?iAAD!^^gRVEdif=G=ruU)~~C3r?Qj*ygF@klsRQI_>91KPTdti?$p~Pg^DVo z+Clvl!>d3PJ==PBB7Jv44NQKJWI83Y$>C))d-(@M5P_zL%Y$}K%O_^&3JAKAjK^;# zL5#CNjhOcS(BFzsr|&?mm5ZHLc}`sIEuUkOf^;#HhHEZSPA9=6r;GW3Pq%C!v~0=< zt$+}e`PaH&z+vc{w8t-Xa|51GaCW(GgRe_)m(t>@L{48Yrh)2nE_87xj9z-;Dxnj6 z>QE7t9qI*xMYZG74-KR$+VytLx>>lIHPdlg*^EiSYFwjng@@NYD7bZ>fj!|C+(3Z$ z2B+e^@ijs}`{WZd!!6e7Ay_>Dn`p;q1(| z=v^qZ&Wf{rXhA6%_M1Xz@XLd+Pqc9q>@&Y$J6l%ak^6Z91t?8X$e8)>&n2NA=iNiv z8CQK*7y#ezEFC!>Wbgtul@8M;nzwnFOVC|1z|j7YUUiSs2Sj!LYMuRmU3YyQzFq!H4baMZHGTY=$t zh1wH$@wWX~S`epTr#YbDCHpP9p()m^HhX}U>`aq6KbNAqx-!6N>oaS|Xb)qN3V8YK zLNXjH_%eUN%rl6c)8rzucxonW)t~jtEKKyOA?)nz*qx2jz6P5}P@uEb_2#%jdCE_f zp^oacC9-9QJg(H2i3k32mM_EhEf^Ae7&<1a7;uenb`xhmClMbAxn*dLh3f~s^s3m_ zpsBAgt^TIv=QC28QiGvq@ak4jhL}p5bg^O3gYc~vy#_I7A^o_Y#|rIhCU9u|36-RB zJoXxS2x@k!=2=?luNT=np!k}e$1Order9Hu0{TlrFt7mR?IX$w``N@-tfRmr#A|B# zFNh$|*NdaHW`5L`+;5HaO#?48&#VllBm2xz;xvh<$xLcFYW)aE|0q88fLp6~L1AxFJb z>VhYATqjBDG-)Mfl6m#sBD#!KdTFh_U*BZPGBSf99nEPEBEiy!vEvPv_+SAke;PHp znuCC&bDexJ!F2g)qV=>@_sB0A&1W#Ix0Q~RveY%%dt^c3bAx1Fx6q6~m8N>AjEoDG z)~$(lqzMcFCcsa{C68e2MlfMamqpc}Y|S8JAsR^b$wEfB8HLVb7&w7?W(335tCx-q zU@U|eC`G2R64n&+yHXM#or0w^QzsFh>7pNN1Y?2TP^oj13{C?&OdKG_36hT>LVB{h zC9Ly?xW^<3X(>n;2E_tfi;JE|QVZaUbc=>eu}-2N=0bB=yFF61S)8WEk{j z==(9J9m8Vv~(eCfgMa!mx@YprQfgvRYG_%2q|5aKvtor8G>sShA{Lo+{X9yZ+%| zeF=YqolJhE z5ZjuvRK-zP!1-i9ke!Dt-TOr{wf6vwSms&cb$mI{MwiPixK)(>#uzIZQdkd|$p6?u znGvA@FDGIdbA=xpPK?|gAvy5ue(}>g=?+q(zuAfP6X}>pLFH5aF9bnDv7ITnqZlDaJln}F7W?9aNZAm&iY~J+OtSF3HmeoD0=s-o#7axgL1P4csd3O`j zP{bGsr3^BkpXtd4*}o1(VZBdvUv(l!x2~l_Z86;{7gvfba}wk5mp;7159i1cd=9{c z0o7N;YS&Fd!1*GEd-VH4LW~?pV?Zz!>7a)=xEDyq(s$ogXQ}&T>J*d*>>g5>ULMLbf-y) zv)3F`Tk3VNT$F>a3eEI#u(u@%4M3!ujEpp9iK-V(3n%I*ma*)+8|;Em*@7QpeI9v<3cJtiHDSLZ3$>Ww7_?`n7N_~3t;Fh z2ZgquqjYNH5>Frlq3{~cJtTT=nkl`fa06lL%T@7hHKiy`xiwtp<~JnT;nyPB_u9o0X% z>dJHM!7ZEdL&UWR2ungXa8IK)r-fi4cVwY!w$BZd%NL>|Ad2C#FJ~09n0u za)*EYk^!5zpn8)9$+Y+?9fy6=T(%q<7ePQukN{Qu(?_fd0%P$4h`fIws?q^1_N{Mg zDR3ZNOo|epkTSqAmqwFFxk`fDlG@(L^x7#67uDIjbdCga0aiuER|pwS!G41~9&dl8 zfgi@IPEP`hTeyCuar&MQ3O2nGm=0E4xY zLZkC+9i|vtd&&WxX-J}L0)=wkPD^LU%b9O{yozfRhn$IdC=eQcRqLkbXxsaFu5#)7 ziLvLM8}GwN$y2X#f|7RrEk55Kp`3?&K7Aa`*PC(W*!%=ZCiFe8mwDyb0yFuW{`v3> z%j^TWuboF0%%gGA_+vD~j(n#-9jUF&?<6{ZjIZ`r8mmk#ksG`-|2mwfp^s%jkR6vy zYLe#wctMU@v7AaWzFvGlZhvojkx(`(*{CnQ|33Q>Bdu}g*~(ppeOKABTzUb2R>R2r zHGhKi0~iZeP-7z){$ww!SX~PV#6)WU`)3a|-ASEWxmIIq%PiEpDJw1`W9`QF6NHCf z-_ZQ98q8fR=X#xFu>Jdv>#OTNe68YUQpuS|kCMMND)i2(&^D~s;7SV+8|(bNzYI_D*3skk!o|ta*Q@k4L858F#HyoHetDQl(V}~oQab(ypdT)oD^Lu$#Z61nz!|KwP8`uaSN&= z)$WbV+-~Z0CGtS?0PvxNHkzGo?K6ky&keg1(5C$aT+>9S3X>W|xSC#;gl-rRA&k;% zK%2IsKoq^g?u+&9VK3QEvkV^hOnK&Kfi+|El>6>h2|FQC%+FM>-bRDLRRQl^rv|R2 zOROPoOfi3PP3MoSE@Qk?4R8n)rc|2*J@QsnSu&qDNCKEk;%jIIo*9=62*zYmVnk}B zC9+Y2NL?2V-CVOwySAO70{BB%Sa5e}jvBOYpm6C6wJg$0XGWdETK6&iiQ<0lV+N!7 z-x-FSFCUAIF|`Y!xBr46;n#t43UCsR1As- zpT??~873{eqPTM`D-ti)kY|KMNu-IJo4buUC^3GP4s)8-&=X8}M&|k3KA`YX; z=|BonfHCUEC+?4$Lp#RK6AoFGxc@wBwW4R5C|vlG>&{NrK~RGDX}`Mb7BZ{!R`Ag~ zRQi{VD)Ockt8E@LK_Ylu6G?hLHmv6A9_7sla(8^vPjxisdZc#%BYvDhzY_9oOM)g@r8+kXMJyIYL|>il&efYD1a zH&MU9o_wa02_<_S<`Xz>D*@ILsl5s%>bjw>*+n&?dyco#6{|RkcF7_T6=7r>rQD-| zC4$Ng4Ty;gTXvfMHrY39tJaP|dzuWaulRy3`=Ok|&#E zP#+{I-(1)>V$v5Qg+AIdPPBGZK)tSO<=qhqu$#o(!ef5yfh5!gjzb5JbgUR^r)?nl=%oS18%|p_IvG;{wf!xQuke}8- z+_Jy*hbc%*(6kFOzW=AHh$^7p-uqKyU>_u+kMG^*x7#8xlxDGTsjoyCkFppZ!6<1;^+4RIc*Y1!nD-PGsMJqQH3q!rk7l@pj zu%8IN5Cl8pz^eEg>#C`T^Vx8y&DHso<}w%$OyWr2;`9znvL`5huJWakBdW$?6wz{u zDmjn2I84^2*Gsmh?s9XFTFVYwJ=a+*C6iQVcEX5-(CbkeqSC$g9mYjwmMWSY>L5bP zzvrv(K?c78({k)279{<}FDlVOG{hmMmaLLjR?8U60PU4#;3p(Xz$0tNT(B4EXitVp zBwJvv`-c9!s)9U25x-&8>eIA0gl5XFR{H8>>gGE6y?mAeq76aw=T@#;urO~hLoOAn zplwc0;hMb_iWrM~yOwzTBE%S@jYT}OUQQYqUJhvnm3g1ui+bprNJe(qB(!(uR4=|G z(Ux#d=ed51z~F;*)2`>QH+(NSS~b*(gb3VDXv6IE`0+VbdvLL6iA@}ev#I9#AL)*O z281%WEFHv-2btLjXGZPgYA6!1rx;~Ma%V2IiP-hWm*u_GeX`Ny?{%_owc95Ye3`29 z^$>SyMZ(%dJC|2Jhwh}9X|@G_;_=-s;($!-%jecl<#U# zQJ|d=g)IJZI(3750z=eS=Ar^`9YmaPw|g#`VGVdbQzd4S!- zoOGUGM|`Om+p4zslFc=vM#K_ji9a**<2zf9{l2SGbix|y&dkpTBCQT|*TYuZa6)F_=`>(Vv*4g1YE%CnzcT#5r4@IY1$ z`j-w`Vr0L2zCu8!`D150P&=FNgCQ<7()vw8Z-i2hww${=G7msp=Om$l57nZWw8RO% z3G}t6gA7|v7mz1wO@$b*(e6K**0yCUs$S?Z3wBAsR7;K*^76WYEBV!! zyhgNKIHnkkvx7=uo&jV`P&TUpjwZvrg7!LG&_Bvh<(V?=8N_WzmbcyW@ll&)3;^>< z;D(hy|LdzByX~tO<~wBU6$)wIS~-erF_%*rm+!AfWfI{tPnjVvGA|WVV5v9ejshDmwlLk1<7=q@mmoSjuRn5i!C z)jZ;>PDW9_OPlZ68y%a1=+ut#@E)zz^ytSE4_F_1<(?hMOBC1i#PlhKjAknmK((!~ zeMPWkXJ_HEotxI2@#IdAVIiaBp)G{Z=G4L)9K7T9XyGliJ%ORGh}unBOxm{m9*M%P zMZZh_xX$5OR-dfR4w;9BTu7)8p@$VZS||{khYqQ=KLLUH$fCMZ2`5OFnN~k2@b$Y9 z!>1(3Zxo$OL%-zR%^2uAn2xST#j4Gm^e*K-{6AP^2onBXedcdbFTeE}z@JE&zw0v` z{{tw%f1}TE{1w&nANqOxsq??C&-@wIKYIBO^cf}w*1t#2^r^{M?+zig|NMG61kc~n z+1kuzLDs zl#1pIc(#Ko^Yco;Ry7Iz{1 z*S;ijtC7{?Sd~adIQ~SwcxV=_pzZ87BR)p~1k4}Hr95~`yRN#MF1qi*kYSyty=Rd@ ztGLLGe0Ww~(reo;O}&h^gS*?2gMB|DgSc>!oq6%jUkRIvn+CIU9|vyxwMzLdSYJC8 zRJ}x50MkY%xQg>r!sR1iCb@9w$4XRT)J9Y48N=zr(j6=B`p{vNi&WG7#1tXCQxQ`7 zIfMuTO9{S;wThe!N2WFTwRz#$`xXgJoHyVcW;{HerQu{GzGAQA4o(GC*B=ha`w0ES zty*4#WT)3tV-%L1B=YH>0GCSdH6A^Fzz*GfFiKe*8u!Mtlr)N(JfQIX7b)QxXnk=O zSUcMW4IIRQEV`b6xGJBazKl5-B}`s&XK7<+qH;p&YPMk?D9taISZ?JJgg-NEx?4T{CTy4+r}g9?vbpbo5}||i;G|I0+jsz z$nXZ)1veOk$qQu6%{%r8%rJYUSAgK15{1D03o{wgZ9&j2F}vlho5zBGv+DUdI3oaE zViQhgH1$d(wzVnH>N=0(k)Micb{hmzXvG@<_cZd>$rejAyaEogx|&HTE{}0`{l4Ao zV*1s2-r}VlRH);tQnac)&Gv>I6)u)A`!TjFb*@71cwOk;ug|d&9`;))(SD#z!ty)( z1JDJHxu4U@E0apClKfEI;A5dR;HQ!RB!+%osPf(4)qSdg*$IsU0+NyKFp(K?u9tSl z30DvUx8yh>&z_zDc-%=+b0zZOM8^fkEnEppSCpGdfe~VAccbWd=~(9x=8c zUkA9lCrOaqQ}k^^)R@KZ>mE_btleVQ`RydktCsA3`fE_2CbscGd{G1V(lccSHs6)m z?b21w1KA$FW!Rj=9Fkc+jP)No1Y%NN&vU;^dqPCu+Lat_#`)5G53E1|KOV&v!O&LC zsdyA!O{1*d*1PIr9om+!I4|N=s)V_1+*FQT7pD_a7&p!&Vd$JGFNi^4hza%G*$YYi z>1z^jMlu_WM}Mn3t1m@()w)W^CwD}W1wY;tTZU?Q511r80>4i7bTc%R=H_k`f|a1#^?%26>EoK;k(jLK^F_#5~WrFdFXQ1h#%oP@Wv1*@QKMl;H!#pW9@2H zUK;CzgeNAR^?~#(j_rvxZRep;)d$|cRM&-RV0%HxtjbGNZ`JT?nt4@&vY4m z$;b-?>`sa20Y$ZnZ=~jBdVe?^UkgfDT+&^SQSk&|^#gF8t~*hw;49JS&Xp*_=M})P zIh2?lz~Pa&@Gl_0UW0@a?bE29UCNJ$b` zkj0CoSH_F4kw!}q>eqWlH0NESfhcw<2Z4mQ5Z7;pS4Io!6o7y{Gd&0oJPBbL4PHg; zr_rGWS*1HMLsgclOMW8`3cVSTz%{{`DT8B!C~oM*pxPd`a9NIWkF^`$$9~%v2?ZKq z6SaL3RgJ+@XhVwSBK`E)$Zts>#`V>ibht~JLGLl00iR0>MO;|*6k4bot>-iH0y>4Z z4HcFF0X>YX+K`1mckkXZ+a}g+(}TiVA^{!$;bRvfV#iH_Ke~>1M}>~5GdC3q{^K0w zlZTJnH2Do^uxat_mz*I#=aG^3e8FB^XsE-l%$Qy)U-!no70I1$`-LRv|9sZR-aJm? z!+P?bY4R@L#Ju|T`4F!gUG}8FFaUj~iIJCXVlLeMN7A_L1vqw|u2}}G$d%R?z9s`b zb;`YUYA*uw1Y&xo$LK>nT!-(&F>txYp#0`}^>qqg^xKC-p?^@(&*+!# zPT>*C1#OL30|X9pWH)viv9yFsaJugldcyfyk~{1t@;4fYVJC#Z{>7b83ygOMHNeH{&V;T(X%GEV_a*9 zy;51ND$ZSMd4F90z-E0Ow>r0H>dJ(uGazA26U>6KvinIlGzAJv=B+F@hIQ1FxNXD2 z|8>&@PKH}odfPjuuirD*-Z~tw#hxW+{*3u~;52ig5ERbU%bU;|fno0sI8c+fD>@7k z!|okOXrcvF^xFgWw~vwtNQ|7)hrYD(>Ag46**wqz6a)+*c3p?}_Gzn#fipH%r>L{e zj}&(G<)J12o_NRc|AI&Z{4q}di+J~!jP~Dx%=)+D-9I9)|09Srj=%ZU{_mNqIeydj zpNe3qz6c4Yi%$8s9L)R%ytNYSeb7 zbNY2_B1KIBzuIv%rJ6^gObsoP0js z>TVWw^zNX6C4D>RnPgVfi0Ln$3ytJ5t0k(^#^it>W?!WG^rHUbg}ZS;z78OviqV}$L*fgDvrrO11@!(>Cvh*Wz}Nf|ZW)h~CwXoeKIeW15%h*N2jwjK(f*R0OfzM%eK;O= zthY$xthmgh=vZ1u5%h@EOxhClepBqPktGB14{Twi-|J47t{aLRb61vDm+x;=5gP)v zYqC4o6kA1WQwq52J(d_1LsB~8VVM*^85eAf&810Pj0nrbhUn6?Gge+kFz=`)0d4t_ z-mGr8xhb4xz6PStz@HXaIx3Uz)R&tB$=MZ^a!zf>mSsajeOMjwhm{;dA*IcrAt98X zntQ=o487E&gVrmkznKjj7o^=J4V&aDYCOzqv(+`#1@D!Y`+_!Bl>`W|Ozv4jzE`x9 z7p}SMp@&*9$CIn-clna`E}&i^k8E(~v<0f+fEczg?x9{hr)90&Pj0}7rt%~2nenlc zb1L^0n}6;G&>opoUhM&5Oe<}hAQ>Clkb=e+Xu1h;jTp^g!m}JXFN?eHghcZgAsIHbKj23lvNb1Fq1x5J zVlS+ga*x%Cg_DOZV z&rdJZwzMKXr=R%CsGMhof?tyq4nvsa%_HgF!?OKz!g^r~*)>lPO*!b@ zDmmoGg2-Bln98)ZMtx7nJTjK9NxGE7AyCjybj_$lxy8atHt+yoIh!BM3yRwk)61^; zsu~RRNZ_d>z+yE@JQ5=hur&LWA)jZ zGR|S0rv|rk=ArB}B0jNeS+_Wj?>tv+Pq7I{ArVB^X$b0#L_rznBGG>R3}gVk^79?m zFdl)nKm|3+uE?Fj3jPi#gdJUG$X>Ay!$~z3LC4Op_|${sm54DpKY#SiWoK>09)6liQ$A3FrM)@W316JJ}YQT;x!RIm=O zcTRY&3LGiKV70SR$=x^#Y4W^ZVrr-jXsO;eL)kL`M#^w+sE2q<0c;lLuX z_f-ayMxLgh$6ZO6q$Ny-K}(C4AayZ~{|UcCg_wS|aTurxxqQr{=GZ}PyZO)0(jLB@RG$`Ad%4%^AswM%!{i8iVC zbt&3{D30~>#20OaiiCIz(tUM_X7$gxhCqqwE0-a(x!f`rZVHqnnPeR&uF*-+i20ri zdl~hn%!gGVrIBB<$s`84xeO>9IcC#pewk+m<*#fcE(4eC3Bm`YjTmupW@B}9lZ1fx zKMXIxuaxe>6MwIp^{GN|hr3?#6%MOUk?bx_aM^tirs~f+;C0ycn5uPZGZll$Fpe;qu=%MW6sK^8 zv{hwlF@Rz{$i9{l=D13-%opWav=1w$6q2;KZgyyMBS5QbF^vY(Z zO&Zk^6V$}5FP|r3tz|fh*l;yi=<$sAXtYbdSJ*_e=o?=6o0*d3Ak1+bM%qO;vaT+j zHA)|EDiYt6VNqJelc2uG63w@panaI4=HY|PoHl?LSmqPR*cBPIZpUJWEfQhc)U9C! z7g8cR`xKD(zz|n@`UNRc-nz;7JW`|)Nts2frQjLwoS8n7!bBjZU6Z%)CJwuwlK>UY zWRyMAqAf&wkgn|%o9rMuPBfDo2RK0J^nJa?Y5&4yo2(t#yI^?V#>7=05P;Bu#Di0d zAgQ-yM=29f5f}~;)^hf4RZnpMThW53V>CFyD|D<(XXjJcM9}X)3!?>P<{GXo(J{5( z^ow7|H9CrI$&kf`$L~SC>n0L338!T&O&Bv0f9nyK-Q3$RFol)~Jh9zt}7W z0<9a#*K}DivNMM%xbR>!mLY9?oFOrUmwYcldYGV+1jL>9Fu`UT$`TLfuY1iUP>Fwn zkMh~<)Bg;x){G#(sOG@IH8yO`@S!A-fjCA;40*t@Tag8o6en|V^bJSV{H){|Mg>Ln zb!4JG%Pt>o{YE?W)L727F-s?vKuV~6al!6pZKtSXduI8(%DV9abcAC)>F4Qeh?m8L zK5;WC&m0uj3DW$DIA@WDbl5i zgv5sB%))SD@HlUnq||CVzw3tOo8S0?3&u;XPZ)6r#(lMs`*t{+f*~!@1;npGiZKLH zJx^4WbI4qqPMFY3zc2p3NMWAn3y96ki|D$&7*~4~Wt|J?jf1?zO4h~?WDTg?H_~?A zcGqQsI&6M40t`4}+P5m>Cl#JTAU{BT*%aIy6`lp=qtDSYS;JoDCsCP@scFqnAJrsa z8%~VhI>R1+aUYGv3tYW5TxTfKpQ=vna$+dOH&Z{~LjNl6UW2=Rh(o3VOOprFVp-AW zn_5*ZYmGx74{XY{$77_-KMT%BI%&wj&OWHXuU`80TYu6R39q(MH_#5a@r2Ugx5XH# zh4-Vw#RNM+hg5cPog(!zWN0GxBWa*Vz^Y{vXK6Ykn4h4BU&+(XSO_GBQ*-wxERA9? zTqTA}aq%ZK2SmZG5W{_OcQmY;r$;#XC_0N`5dIqUkqS2}lpdi3B@zz8%W$fh*lz$2 z{^Tr+i5`LMt!Jt8!{Numix>3Y)u8?s;r7Qs{>LNdUo@z{e02VQ(xCnepu-%0^FjJw z)S!M3>p#_?7+Kl=#o=cyWz}j`6fyAP4#mA$!}~S^p*<{3=nH@Gb`if{0lI8i5s2aP zC9vbm?GLZSyu3a#`K6keE{6X73a4Mzf$1rz2pet8`nCX$bQyT#T8i-G?-}t8!r8}B zavpZ&^+f%1ob<*faSO*p>L&I)nsj943uIx-g%Uz0tij8haeRAWcXuA`yv@&FP|5?$ zbJE{mE1&J}NAs>K#z{q{Nmf@h%aYssaGa8f<|#e-(kIh$cXeC?lScdPI6I%Ea5~Xu zZ)VfxHD8?ooha5;iG}v_OF8A=!e~Yszqn}!M_Y=__$qOhVSfK9c)1=s?Pw9G%eAZ? zz&gvq&N?z{=Z#U@B)Z zVz9rDbeG_ngKik7${;eZMWd0RPA~HGG%X>Ne$qsj(kB%Lu2T+6D9) z8BnJoT^Uez=FNZ^AlCp|Cy@R?ruX^366y@#q@nBJ2)??pNV%iuckGa ze4Q|mDao)E;8}YQN!AR}A}O#+jY;rk)^b8ntr^K_Jwk;={17f_rO2V&Qlvu|?!OR% zm?VbmdaR21$3fscsInhp+FpC_;=_{j5zD%Iq+jE(iys$wrL$th<Tvb&X#l#l?~R;`QJ9VO4h9ZYkB zUKJ_=z-~fO-E}}wxbD+y)4_Wm5>j^fsh~(0VJnL)-4Y(A@+RX07fd|H1*rzPVT+*N zbg-fmdwPUky&yBRNu_PTYP4-BA~F~4TasJY6$Uw5phXiHw+V_|BS^(!+OUIZ;Pm?< ztzM7@5zlR6m3uSk`R6l;>HX}Sb#39eGsmNEnXkI9-XKkOx?BpBh-571=fT+ZylZvu zn%!?EBaS8(8`hf6f>0=-&?o|70ues zSamzQ74D){rw_iUPE~8#)jjrl0oKT{*%Jua6K7~~P+)CgpU~2jG%8O;!{vzsAwhS( z<1=zITC!GBkW@=pfAX@N;k2|9hvsxHZb!hcUY%=k2N5Ts5{u!!WYgP3#lI*b?98%3 z$QGXzis{U`M93bR6#9afl*7#kj)%&{O=Vn41C<8%GY>+C3fNbuy>9f7DzjYfJLcmK zyv}xCs(JlU%YaIvBU}O(g*`(2VGy5v#=a!^w?z);VK$BH-QGQW@agY$P!1K=cR16R za@H?fRT?ERZKzPhvW!5={fcS_Wa9i(|(vW0)7i=>gSR%ZiF2)0wGRzAPQZ5?PWY$-n5@Gxr4A`2#Bn?~?4O{TxBhAah z(9uM-wZj_OOz_Pb&-O{x2EgL;nTKqz@i%^I*%Uq!=n%zDJDr~>@?>98SkhM{9sWds zF$O$31|3}mnnV~4Iow#?0uImYpA{J3Lw00z$b<%C16TLBm&;(2(a}ry3z5gh^D2#z z{l-feHW~t4%E?KP6wCoWljND?6EVX##@^KVr*M}nT?5s?loxQ9F4GOQ!YC3J4iFZu zjOh76;|)r%z-honNFNMtRq6?^NJ5%$b4RFiqn(M-u8oDGsfm3xv5@w9f(Z`Az&N2MU3Kotce;wH?7<5`nbdKPoV?u>T*x0VO*}qd%D={=EF@{i~UwgQ>m7M{1tm za0Y)nn3*{UexJX~nAm<3&cqHNU}5_GkNkh_VEvOi;IF#OOuvo6|2GHV!-@*v_~`Ki z3F6N+fQ^9pBgF-Pg^_@jfrWsHgYC}=U}gXF&cOiqQx5o`^7rQ${?Ph6DFzE8!(UGr znF!cET#0{USpq&_HUDp@`KvAq^G9pU%vyg#YWR~u;~$dBzp_-~pDg{KuoJ-WyKe>h ze=?Mb>A%I$-|YK+{xuZlkI7&lUqkEyZL<8P_4oUS5ucgyV<9kn(EV}G1o&-kXZc|4?<@A-@E0GY0M@^r z{=R1Z5L#K7*gy8l$CCQp0_z7IAE2fzA5{LnW?^CZ8%zJ1@PDvWz~0~^y9WUy11med zke-dWk(r6JrjEZ4%R=LQBcs@MT7SDxM-O^Rwv^JEXc=4 zSUx;!es4KZy>Digt`xubJHhV_Px)7=nWfPO7|XVOdL!FWbbgdQ@ z%j0GB4R>iqKUH)T559X%x|%>t+c|r6Za&<+mAZ1=r2n+fxLKRzf&l~a&_k_?=5cfz zJ2EM>O!MZ+)TN|RQ>|O796N;QY9a(08;A`mi8x{N69gJ^!P#VXzG@4ILUDZ3!#<>j zAJ>rQdU)LhHUJVd28L7B)K*b)~f9G9KN@LQnyBNov_k=4*j%S09dHl*01AS2OncoZ`dka)-L2rl(GPb zoa%xJnyS@nyTU{1(Tr4pk)5%qo4UEA-ArEJOF1+$c{ska&TG4^fq_^=I3^>vo2jAj zBjSy&qH0xVrb_Ppor)_ZD#&CtoR4X)9|{@Ql1;9TWDLi$W;`qRN-~aS1`9Xma=OA1 z0~#hSR1=iFdg_`HogD^jL?jfL$Xg36u1Y$`Lu87|qO`@PbPgag=*j`Mc6vI_kku*9 z*NnBSQjTdgBGP*A8KrqbWayKQWwLaWU_q#Yg|t&1x6($uW-v>vto1y}O&-(y2l$kd ztHC_BMP&9t{}00>VWO|e*~1TxOj)=2t2+{LVUoDZvzEgW5OKr2+??y#tmMN&3=*Qp zh-4fnOp*rRq`0XOKc=l&c{a)ec6ul>73|HXY0~^?d+KE@?G$IRf^^~yk~xMME&I{C zU9OqL>NqHukwmJE4{p!mTrH$_wtDN04Q3I%2N}KW_wO@^oTCsc-hfT#yQS@-aneFO z;V6fG78Ib=GUgXo6&Go!D_gRfkIVev<&_DGi&>BUCWNv+vu*50yl>koq@gN%UfUX# z5gT_rC6{Jq&#+B7a7}dD-3eBEtnD{kX)Sxd9tgbbJ0<|1CLRB2d|icNAkbi*C9U+E zzkV-p)qwCat~4R8>n!u?j2*#`R=+LhFZUtM?{i7@Km65W!VqNML7?475)#*~srD zl427y8Q00^ZRzbF0LBnp<4l#1Kv%m+uc|v62 z)BV-aV%7|)fBb}^W{J;P9|x?!kp<01er`znX5>`jG?cBEiD|fBHQEwuF`8~Qk*=cK zx+oKD;hnSF6L-OH(159FDi4f1Vv|2TfT7AIJEtGS2u^*_clCHC?@wKA8nbOjue{cG zC5p}HZNeJ6jbSWJCuKL8d$t;Vt@MK|-?a+5F2sc_A5+>X?k6*MYPVjlyMbnQp0vyj zTy|OyFzLx*9!qoBHB&NG`?N6~^XmA%Xb@mkbW(Jg*nW8&F6GclZGU6oWRS)XIoW1u zHfziwPZ;x=c`=5n@g>#F8LrShFhWMs{@|7@bnR3WO5C*tv&b)YY-$X`6?aJD@cSaO4tLnGbGRm>Rrk@q_RWwx>d|nVF8=v}xgBM*xTfZo? zEPLLR(7Xt3Rcp=|P(9s@s|Uec&M?2l2{LL`tDn{~(G7E1oZX~f1RFsKjxFWhv&%}| zN9CTB$bH}<$qv{qcX~=JzcAhQ)>IQsbP!$Dw*zsERqtWqxLWG;Se@{GAV)5rqM_2I zV*c3h#?TX$pEy?oyy}Q?k4_H+?j1(Y=(JaX)83g`b@tGJrNyke3sV_6(CpsYGDBU5 z`v9m#=DRNz{t$SEq!lwTQkP&wQyg(u*WFbkbjx)rAIBb*?76icum)uS> zziTa9^aoil(yONsn?!k!BXX zD7)rWUXG9(-vzQXFX1;4tK+o*-wNQyi&l_e+-y#Omk(bHx)9$YjrUmEu%Q<0Q*MaY zF2KQEXI++`^Jz-C+<6v-zf2!1oNk&pM=nC>I?+0Tu#5_4VJM}op z>L3T7qX#6c!GW&o4B+`0d_nxFGcBfj@?(k7rq?!*4fLlr6-r-JM9=A+81_8HTIN5V zD4vAa(CX3`T9XdzP3R(S5@cQkd|xZnD>O`cZi-bIB>gLw0+~~eFv-Ld$=|BWH7e() zGC4{=`Ptc<1%_ZdkO>H}(=d=x*J z9h?KY%S09VC7J>{0rLv>AKlc;Xv%Qj&{J`2P?OvRb8)U{l46}1{3i;0^BeM*5(#ExH^wV7lJ<(F41zws2kOSqiX+T=&LXMm0QsIS3_adX&K=)A|w>+!9F z&dROG%PJiNJ@dKF0~W3})+L!>20CHH4=Jv_$#K9M-_Mk5#x}U~?eJP4Q*X1(0{_5i z$$M1P{<=i6-nT)pc0pdB=CJ7eKQBbX3!?>@FjWKS5KnjX3(~kt#zVY?wkUie>n?F3X###UgV!g9 zSz33(MJ4?6k4r(3bduVG*T*vj@Pqxwv0X&3-&b@^>9I~MTO;5n=Mr(pwd}*_xv{Tv zinVwaG+|&&qo-C+Y-7InE{}#O9YOSo`06B649;4PhaOWa=osJVMF8}p{FCRYKq-lu{sQbpTxV$N9{(^#NmL;58q@!k$&TCbYTC~|d zo{x5_5kJY00ghyn%?)iE7_|1FxRkiDPy6fYD78gnk{U{Bs2V2+J&Fy5CZXDVh_m0I z5ZFw0((yUUF+xo$+;|TGx>P$2k1h6)JuDqRNs~1CD%V3UUakY!E4#+}WUW{?=Vdtb z&K>g!y;)b@+n5p$27DWGn+@bh4|bghV#p)0#Gs_v4pF}UCO8)%;L6DEy5&_{kmuxA z+z9$%wHry0glDivSn6?>{UzaIV3)x>zT3sF>`6WR6VDJOmlmkuE(H^`szG@nBi?T6 zRIVOr3RjE3`Z!()JfbZcbsuFvfWpLeUi1+-i>&~^!64F5PU@GK*AT){2F_^6V%o?v z!S)29U|8rPP9NSd+ygPuA4ToMo=^`#0e7}OCw<;2GyrF7{B`_w(2;U{cYF@Q_glrL zNw(FQGlGPXU#?#}RPXxS6B7ifU`*06i>4TWul0$%!Zn6kR{c!SlUOwGbxwNbLk&5O zy`MJ%Cj4kYB>3+Z^)>@Q2 zxF*nHqKG7zW`f-IuQN&~jXi;+05gc{Utn|ZPy>Y!8^)gI_M>n~r3Ub4_X?BITLZg55lyn1V*m z_k#~O*8;o{dGC#RlGUesE4LTISl?C{dlERyEX&RRIY-5Z$p2j=!aZb)%Z1ivxox(Q zu)p+Q1Zv(FOCxyS;dX$M^E#abWxDBFv8%@RcskpcrZHRdR*b&bHjBFN>m1TMYc0FZ z^O1c5b`?0gE}K2QhsA7|Vaf9nQm=LjT$J2cGd#(hi9sQ#vW z!9UV-4Rk$FWxpCZ_J!{J5_U6%+kXQ8hI^W|wh8PM@b3ZE*0@$vzuUZFdP7;NUU(j9;%}-0u$%{rNRLc|))M*MO+kC?P^6Tl_?9&3FZI+!Vo%AC6A2D_O^g|YFeb>o z5z(#zbA|3{s&Bwh`jIN?5iB&6J*zds4ZUpZ=>)J`+9hK?!b6Oigq|{T6bwt0AqW|$ zgEu5Q9tDw^Wezzh0|_6AQ8*3V3NsEpFRc$H3x%vsNkhDeloDg;5lI(IZiQ#szeF=% z2YE3`lbL~p^yCcnlW!ylwh7}7h!)V@M%zo)oW_s3j*j+llEuFO$p(ayyJyN&Z^coo+x-L?-2&f1ZN^IOU zVjvVFg~m*q(}=LF9oN9s?T{h`r%5!3;2^6)$c80^?@t918#H$iq7n0}>j8ZL(-w}N88mAx zFz@lham6$tZKsY2*>5JWrzWea;%W?hQTR}RZ707W zkQ@L%K^HU1%@5O5kq+pymF~h1ipj7h%Q&w54tO_g6hVx zA>kLkIrke~Y-Vax6Q$8>D+$eW20NF_qol_}^Y7q=C1G{r%1ZSVO?ix5#rpiK)8Q_^ zYXq-Uhb@eQCCU{yO33fP)t$Jw9T`uFFjtWv#znmRnEOiIg;;El#DSq0SEq#bzK8%v5e+KpLlvxVONJ?#ldVKyVWRoa%OPP)BN5I5@YOnqNmao34d; z%=y-BA%X@eFsxZmg7r;i&00g0F{^KL{xA3k5*1K(C_ZzxPfF4F4l5g$Bh zs3GWt#p6%F7d;S+1wihNN5iwl&yMN8z24{HV|woUnu2XBbv!G~?eBXW4i}m=T1@dP z_dIph*KbT*RK=Gf*pG6&^e4d+6LV>*yxPm2&tA6aJa6J@sij&NYuV{0+}$o-U>%{4 z3Wp+YaTHofN{#}5`6ykGA>-3bN)b+8(zOgT;9bTiuQ)?cwcYgBAj=rVSJvf*)&F58}Kw&~qbz1M|uEZN(KyzK4=x(>$yl5jbWj2FsD zV)ta-uFQn~^S6np;J%V_X92@VZeM01JBVU#`E9Pnidpw+xl3&yUoIy5$fZpj7H@TD zg~Fm@p+RG!Skz`>wkFHx7os6^$rKK9=35`e(<>$O)kxx11qhRD)9sp~Q=F(PH zM$yKS1)3qs)*=$kA1`gVm^5|f`jcrIY(z>38g8vWUpHLX%k$m*i#SuEvoFM)#3S;i zvos_M;JQuDVa{dD4{$C3x0QqtQArzJ3Wba&tE^bM&0G|NH74GH%ojZ!x(6-uv-^`A zjo~M}F;T4UR512V7ZsY6Um8f_@vCF!-0-zqc28gm-40&o`)V(A^YveDWfLz`1-&1E z*A9I3ukm;8?C883iropC18k>IwL-KIC0>uAPM!S6l@hJ*XSTxy{aMr>L!k1KhGR~d z)Eo1JKKB>l=$X3H+wCVAZih6KpC1Q_VX-9&AOhD$>Z#Yx6BS~{ zz_;*UcY(8coPDIyCDk~d)op7}%Za-4>d9gkQU3(3b?PMei6>gTgppQ0 zb#VZ1G`}GF13VEN?VKS&<2Zlf)tWXR#8pdYZ17rBI#hN!)B8Ml8N6O#ziSdU6Z|(g zg$f3?1}`bdyz~W()3-Nl9xGc7G5!9$lm}@{2r@{Ki;x9Zo8$PhTDsNKQA?sDdvRNm zydqDJt>X|OEI?rN6fqu;lDyQ_%TBY4&c`bw$yaMpDTkxj@e6uyh1;XUb&4K^o~eMD zFEI_`C-l{lA0~Q>&+Wn7e)3qHKY~R3uh)L1Q4eh08`YXqr{Z`eNXktEp*j!v;$%o) z#siwofGs-*y4AXz!81G4Z`D>tI8!#NbrX|#?B6H`_rU;_sS!$U)EWghdI^iM5M+vk zg+yor<#46ezs}1F+j5Lzvh3NqgeG*XoeC~Ft_`9M(~BI_^7}N8)6ecqh%n9gF1|P;6wD+IuIcl&z;hC z7^~ltA}B8ByGfqjt94|c6~axq@Z6^eIB2`rE=|PfkG$B)9Yg1~8qXm5IysRF1e`!ALp4yXP(=MddF(BTDs4w z8&AGGK0(%K-;^_LQOgx%QVu5(FQM7j5gYtm&bJ^McDsK>Qx6?14`3AKoVPM3>pVTF zL9&6O)$B88kbN2SJ%nWnfx}1D>@A0EZih0GDbx~fzsO}j&*1qiw_b4AcRSn$-J`BO zHeUr(3u_j-XSp=qf#&cYq~t3J13L^*3k|&&E~`B0HQ+bl5^PK!7VrL0GebS+6y^J0 znUIPPN2|f-mZw$Pa6cWhZlntx<2|5e4lgsA(khMNAUi)_Z) zr^x|eGcau8_0^mGoPns5gbAi+-|tE#uzGDZh@<`e1p_f$5?_*8zSsVAgFoR_uihBJ zD&)|+-}(;?Egy{LU}q`JGts9sWq0Fnx%plt_Ks_^(c1bxUiZXc)YB4mxUa2JN+Meo zH%lz(AB+)lvgy|dIYGflQ8-S3!AK~dmM4Z6(j8U0AQ8;4*W<$>O}^HV=N6e-h*p=6 zE&=Y?K0?XYXKm94=kG>2YqN~xVKrPG5X;W4JP(DZ`h0AZ_Satf65HLEJh2yezSL~J z59Mb0@-bR-c9yw5eq?2^()Ui{mAK|!O6+2$PF3khh1?6-_HUM4)93`v)yVIz5r@u% z>xZUm-IhKr9=L{PAE$wt@>UvgW${K0rvqM16~$!+n^*@)RQ5*P1L_pQ_yJP7%)Ol` zUGU|U#gg{RZ2>1%5J+bQvyP@~pN84coG*AbPC})9Bhi0lUb$*&Wr_*oSd^1yex31h^VYWDLMY!A+9;eXdqeKfw?1B0o?CD9x zvxoKo2Lb%jgE}Hah;aJMBEowdtP&tbmnVO3(De4rG?Ede-K|LCN|-kZ$3A6!Pab&e zT>jLf;Zaf2P`EQ_|JK^@>Hp54Xy#XbeUdgEGL@}Qjfu$RZ7(yS54Y$HS`d}3e~(vk zcu;*QT1C~IdoC0!0dn6RujTbLq#$RH>Fo`^nXR^r($HymX^vQ8HLoP&yZHVJ-%iY0 zp*^RS3s-xt@-QgV7Y_JMM1J#Ow*K%@)rzHLS_^<7L0SMOQD5mRNhH|dN~}!MOMzVS z^#YT;-B;yppyrs@FvVEvemsItbo9|<(%;pPO4SxnC`V81=-c5?Qu9$A^DKFKyEV6s zc%PWOG#h!G(|b@5!Ap|s!w{VfyhQor4=k7u5&xQZJ{sDydTJ0Vjgd88bz>JeF?`86 zmVEWx^3`@&j=M*A+Z6tLEv~M^Xl8`*UI+8^ewcsplb_2aXmwkw`$AsM#c(n%KC^K8 z;#l0L(@N3`N;5$4!4x}~;m?L=l|LVFmr!#Vp(X}Gh6R2eARZ;t-@U|hE)ENl^PbS* z(`m@4DhfIcN))tU%vzAc@n=nO*%`=or>W;yLE@YZ=B9NFR`-FZwS2hh(v+{SR|02YGlju`w@mF?R{(0(u&=*H2lMh_!IE(%xE6KladHta%G{<8 z2B?T=e@XSsf>@XE@^L4M)`rOiRh0 zwM(vr0yV{Xp3@~{Qng{9gOzs3LbGsPUPZLb91Vn~sb|A;!@j*g5~F8LrnA%IydUkB zjZ8-hD?2>Ucse{^sgTs;cpvjYe#@#(e`>7<_9H`Yw-rTAW0}ZT0Q)vpylFp^)36_SA?b?=q!ng{Ra zDnKAbCV%b{q3k_xdU}{y%1tca=uH;&?0z&z+ky5D4O`N{)})m^&NH>cd%UzT0xKAQ zpDyeeV(or%ziCjkliO(MI{G*Hp8daBqF$ez808?z{h zj?ss?c_e1)#2E&tg#NN^#6pRK>z=Kg#$2Ndx!+t_;rc>DyE7&urp4-%FOhJ^$zbd* zCL9K(*Yy~2<%La%lgHLZ4%l#QZWL95*%4y8dGLQ;PP|$5?jXZZ9)u#i{qQi&?T5)C zhkwOQO+&DAKccZS2fn#QWVezrZ2opaW_EO4A@cpMJ&b)&wIP5r|TZu7Ty zn4i;dy~bD{UQxBwh_?473S*`?TSxWF%vt+#T|5zu6FOb^@L6W6imz4U0WfwdehY!h z5xt!cFiG{3e(b|kS@BMO@2gycE?y}C3Lb6w=hDB=JA_O|=j)U%Jpk2s+F5BbE4ab* zEe87Vj<+4_MS;H@Laej%FkN!n67DR1EY0UiW0VE&(`Y|duJ?8R=)9=@sy~>XSH8E( zYuk$M`#w>82w2PS|*)4(md{mS@8A&LX= zX~FGZ;Z$}rh8%38h$bdy*XUyq)cu;>Lj9Q#yKPD50z=*O6^TROP$>NE?$h4TX^%=5 zef#vntV|WQ#?MmzxY-bH3-m0vSNft4x7z$n7@rPG9qBp974$p}9vUM4F z`9LZv5$G83nj-H9uxQoHULqGLTm&szcg6x#ybvOIfR+XhXyz>x3+bf)bO;EWA1}yT z(U5{Qk7E5@0 zCQTEb+FfAKB(7!UQmGqZ7YOZIZhtNwC;BCU$PJ6cLfDl@g)wPdi7qx zIam792VBVpZgaGdb^0`qo#NXP>E+eyM6b^> z?M_=IS_@rwvNtEKQ)Sr*2K{I#aR+EhPUNYHG8x_zm+st{xmPAAM@|sK;9+~fN?4^< zrc(@<+Su%N6^&S5ZxRfITO%4f1C)p-;|vT8R98}nX&VrKkHxFqbz`GkDN8wo5;s<3 z=Z^?RN5ls%;!l~D*nFSAlAUSy4EK97B6QotA`92r(cpTVTqo*RiSXG#BgCBs!yuZU zf*qDE*^X)m?e`qP@rnmCC-oJ#AYV^MZ=ewl`o8DJ7$9S0xbcGl<=W}Tf;-x6v~c8~ z@rFK(0ZZk)`IkaWthX!GLb0=3n6cve2bQ5vq--)u`(bNLs%||x_jA&^5ZhPY(HWhnmB$ z=bmi=PCR{2G2t8k&JuZH?K;0C!4N=8V85nFnn`s4x^ki&L`%<0UjHBhC!9lB?6yAKVG5@{|*b8tda|pkyQ!7vlTycEqI(`hc=&BGq zlz;Rn^<44jJ*9medR_I-x#c|Fe}MgdeEs*L>wfh)i)Z&K4M!yGAw7h}3;`l0$_?@1 z>$}RmzV)DsH-=A(hI``Q6AT?hFr_WTkjUC6&^7t|4dZVY<|lyxHMoNpX3(m?4H4!a z|FEK2r$>!8B81a6!*peeLL$iY^V>*~AeWHvWNTETeW6<6pZ`KB}AIr(2_(58e+Nz{9)3ToA)WGv~(ipVI^ zuH)AoVJ4L_KJrK!^uDWsHxDSC9)FSeLXz>{24Zm zEJ3HOz{=6lZpte-_%2Chi*B;6Dq}*!tV~5qPNAjIe9NnMs4*QZ5G@`F7HuBcW7=P6 za7R^HGM0{Ch!7n~XeeG1g*aZJsV<|crpPBzi55sK_j6aTD0ho@FQ(X1L@{GUBmTfA zWj+8#7A0kP5vXADD}aKb_Fsj_B8BxE2N+;7ngfjJ09H8$UOEJrR?xEpYl!sg5HuoM z{qWK&)Q;^B??+Fw5(pnn6vW1G1{GLx@0&`8Ac^#kPk~~|M==v4lE?RH?hsIj<975j zAzzfCl~Dzxs|7#-kIzG(0(_?fEh9p|*t5!0=M%;fGxKu_7(gqkK$0N$7me)e0Zms0 zGC~y`h)rvoIzu{%Pa{yqPm^h9H-uD1~?dYriwRO}r4tU|sY!`r@2Mj3i zQzl)baVz3~fmQ#ZdH;6|#($BGQd0kxjsIZP|9?!CmEm9U`u}!~ES&#M*T}^2k01Q^ z@;|96E6YE+k?ALg(?8twKe*~YPLTZ{3HblL{!bhEPv3uy&Gs|Wk7XlZ`^PS_{38~B zRu;}5!^lFw{-Y9^|Dz~68{3a6{JF=;!c4&NGavhpHe~zJhW~N<&mRBSO7@?fU^x}`5{1;MX`yr;Rj4VHM{@niLiDLfAu=~&GZ2$1rAL9Dc>qk)j z)8hQ8N%qfHwjVS3Pw#(LmLCDh@&jX8n14q2dF&r!$?-EU>yLE&r~QwT{Ll0LciYVD zZ2v__{--nw|7Sw-e{ki03CVws{6|kR6EHIWw0?{w=YK~?{wwjre-V=ZuUF*%-bb?k zKYS#^|Im>?RGN;HndAS6NB*}`JuosdurmJJM{+W@9Q0tu zN>pa?7BzK&JL$9Mm%}e)nYFRp^s@eVx{pA0CKk5A^}HLZbrjWhj4*(#=jA%N_rBrN z?etT_>zi6=;q@K8#?1Yy`;;rlK#lm|Rr|cF7h)`*%^=h>+7v0yD=LPo**yz5Ff2OsnS{t`p4z`9%q zVUZ>RZXr8U@yVdifuG2lP+Pw*xF9gP`Of_9h~Te~(yGr{SS@8X*eo?Tp;*as@o!yx zl{Bx28vUTfdGHg|seV?L2T-n19e?i?qJvB(OOrlbHSWTa4hxUNriiz76BybTl;$uU8Crq_UJ<2DNzU#W0X1T344@K=byp*K@Fp#P z*%r}rPO-DXjaNWe{2OlC0>~qHYWR2>*Wp*NBY6PTZlGOwqqXlTFT~*4ZPIB9tECn;<5w(K&Wg-nWJT4ecd+OmA5yRHzA@*HzU(Sa)Z7#FI>Y0&g z@*Y?OnR7`poSl6hF!G?6QA&~4az_uh`r5T)CZ}M}kX@sx!#q~%6-EjNHQq3~^vW7= z>DJTcWGSaqBrcQEEB3%N_6u$gt2fgpi!|?iW(Fy?vZ%4XvD{Yg5hqsq$?56DDLXP! zaI%Hu-6Ms6j5M`PGcym|2a4zFnqzaMpHsyZ zODqpf9?op_vczI_?pWAyhpeq*9lyslpL0enj-Htp;Q;G&%(j4dnTxA|i;L;Stq|Pm zH{akk=0Rd9n`eaJK6XYx<*}dZbZN-#Sbv(OY-{PFk<+0m*s2z~1Z(pvpqjh{AZfqS zAU;5Eeyr2P1=*2in%6D}7^PSu^)~S2oO1;4aCCfb=x^LQKWG%~3_O=0P2V{+5cHms zu;B>L5u*X*U(tGX;1Owzf$2HJf{~?ma~;Z6d*CK7YsB%R0V(5x0$XEB{Zj^LYBhVZ zXXf8(N;P0gHSSb%TyU#y6`!?)*L|-!^>oMd-DWgUDD%PAiT%V%5!|2CwEaP1rp!ZT zk(1X>;NF1hL_4>$(DLY@)+O1lOyW=sy%mqCvo}d=k$>@nKA9-b60d-G?@54FbQ$U1E2i`$I~>~_0+m)jcdSpX z2bBs3Yh;s4y~N11{~~K3_#Y?*hIMpabBmD=!k#hW^_i!_@D1{mG>#q@ZV6=%E}f>Y z|2<9L&FwP*eyVb)De96b!%1C1Gl>Gjpt-o+d0gV<>+%_q`L<*->UnJbQsbEVWkUn= zK+>P~&5BNfu{=4ivo2|?^$=2{49rf&w*87_bhc!bWQu#?V}mbNC5L)BXl8?tew8>F zrHDa{zo!=jANx|!=zgLU{I1%__jD?#Y|IzEqxAZR54ZFTN*cDbk$Z*S%QCuE=HAsttihxjoCR# z9H=@w8W78B46MW-A7>~>Qjctw1VQ8vC~J;;uwZp*+!OlTSAbow#5<{-g4N*7i$$Hc z3W5@R+M%nkM8{qXC-)(JSuqfRK=xfJW*%eFIz|B3ug2RFS&jTP3C|GUG1)H=k3D=97cBI?oD*R?MrOe`YK+`0OCO_1>_u@0bCP>^W3dZt@~={krAmUd=GlZk z(eGqHY*zB#*9JDt^JTLy@OtYi5_T0|mznz%DS5UvUyv5)N1KA%ZHZN^8`S=TM&h#* zD{$Yhny$e8cT1p#^#aR^u}k5%d?uve9RA7YMusvx3!hc!F09oJ(8)Juo}9pY&?&z` zsIU2-(SiMq5Oxb_lk@1^Zl;ZG+0(6Z`oG};v5J|CpU@h8k!L4;y~Xbo#a~liXK+bx zT$}LnAW7i7-`Q7~PTBwuK=P0$d}#2O6ud&M(4q2#RlVsW5RXb|pSjNS!cMq=;X<%qfV@Et1AUQd zMRpR@%;qI}(R(0X$=%cE0}rhGyPExl%<#t#_XPJD8U=!d!$I5!Uyd{e7MIxVtEX7L ztrRE~MM(W4Ev;w269Zn#t_vB_KCp#aqiccN8G`GYdFWPmo=2nRuA(8 zYCmp318ig~p8UrKBqJ__ZJsXz{sU~No_B!bGt1yeBmU+fL9A2hl8>QXeGChOv%M_p{awm*E1Wi$TVY@NUfX55990MP~!k`wwMVd zL0>entoPV%rbYeI(Z)j2Kq{X%@;>46Gmrg!M6e@MX?On$eo8MvzgYP5FoIt|bH%mv zyFuS@!am1QD`V|If05Av;XV*YLggg0FyH|{UsCw%14qw7v_S5F^LVof<%?<6$O8Am zg%}%tAQ2_q6*EfT|Kt*xjIX^I_VboJ#P20fB|$7qHb8fG>Q+N0n_6Jdz2f@nc1fc-}i#Lx`C&TzpO;O ziak`A2Ht=Mb7&M2O52zD_OuM~1RQKy9>ap97pV@-X^d!rEL#AF_00n2{{-2LK>b@! z2Y(DLA0?M!W=Q$3lZ_KLIgR=HO7(1r6br; z5g?nwb}7ao%*sGr?%D#5Su%xc7nuDk(Tf*mg)%DOmW$u@tNtv#zZR`ttW=zMh#LpE zvjW-Bkz(C7*xcH!uaYGr*G+#f{`c$y|B4Ytv!107ZH5AKNte4(7Un-H3G`*{I9a83f}p8W8i z=hwq#@F9Y+z1Z`3AzsPTgBm$T$G=Ck6MRBNQ4$d-mP zz>!FN2n2&}%~6SwGpOxE!}4J1kTY zYT?Od^Lo9Pm;?9T2r4o;C$|G{;ejmKZA5}^5Bo1Lzw)U051E8Q5 zqQk099~vI(LfdXvwQO6aEf9IbDc#;x=yS?1(lq!DmoGBb*Itwy&PK$WAHOnA8-e0b z6rvsCegpD6j2%YKTd)Kj$CF?-Ne0!}4C%DksjIFf9iwtq4jVle*|E~|cpC06X0GUN zcSTPQSbS`4u_s?t>QcMcUXF;LOd#tY9-U0o(a^wAj{<}iZK#bfk-Izm;xuemuALrY z?Y+5pbe`qyz6I0Pd=bj(cvrAD{2s|dn~5ai?w)vQE?m^YM6fb9|^ zmQ=4rS7C%e?aKbuY*3H^M-5T43%(j})Tx&OA<0U93>gGnvTJN(Jlig(<8`;7VQfof zBaKWuu~_{HclZF6Rg3dGW^vD^X>T~G)d3e@JT*S7sx|-+M34w*f@h%RUe#qe%_!bY z#@)ut>w?&~iyV?$wzpDiC_`Eqzb&)!*u{@Ex;MZyuS9SMilb^Br`4GVJ+jmGub+*H zYgTO2*wJDb#Oa?Rwmdds1{XJvEry@cjTtVB43z^vH-5!Sci=#BFI+Dh?Om}@MWY1X?O(n1dtAXEQ6{E zoUTMn6J)Mz0}a!e*_KI4JmEyT9!l+)ieNT+d_j^F$35WaY;3ePmPw_z#BP*6 zIP{9D)co>a_Pa>SdY{9Q1pI%jija!t^E$muSd*NoqMEr-F;b70h+O*E`pSe;SPug= zHf;=bawsIrSEZ?v_eIj!8s6Q#GzpWjTVx%pxcyQGCz25|RpLhX=0E<2l*sQSA z^%6;B4HuNbWROC|cMy{SCqP`n?r`-DqC#k$H797m<@Ov#7Jf;UCvwz*vqIFhcDz>j zz|pU-@pP1T*t~adLi^5bz8$>7|8oD@5wuw{?|LY;#KXC+t)=1R>LjXef6jO31%G-N zlCM+=ID!^zL1CFpO*dP~>=zf0@^cWTFOG4DmBE7Sa9zcHs_>ife;nGKBa!sbAeMtS zE0Y9(!~re&nEJM8i07aZQUK$N4Mf`zp~0{b+tZS ztL-ZNICRk6w9WK=v2xumc-rKD(>}d#Wa|#B&eaRoeK@d95ZRc`ecjn}qA5OZq3iDb zitHPxVch5U>WJM-4b7=ZL!B-gN;QiM%h+!M$->u|4$woKR%d`#*;zL+h!Yu@g2KL0 z9PjVopkh_>PD@dv!tUPX*T*;xt8O$t~ zsP_%LLaxoUqD%!XFgTsJixW2%e&&4&SGgo>K%0W00;3R*c#GD!UX_Sg#*8M#QMsgm zSr<`Y;~{|K;ARI-g*QhSst1&Df;uKXh$M<~K7n~&a#lnjcjwTavc0XmrN-CWVf^+E zyIP(#uEASD96JVTevJu#{Xb5f5|RD%>l1TH1? z{PMRzvQ%0|gji-QDa$~j3uWkehwJppkvPoD0%0Tgfd2%fKr%Ki+Dyc1o z1Ofmgc@Qq4LX)Odu^Xa~-BMCtH$UHU)$;7;;D)ba&A0XFHvaKJ`~5K+dzJQZ^RAj* z>uzq!NMP@(_hn%(rLIkX4g0bS&5623w-@^35f7SqHvpdNyOo~-&Ik~>1QmeRfC?Cd zAJn8SOG^kPlVuco)p^UFT-$*>89p}GG&tk;@-HZJ8D!%DMu8F$C-#h8Y3A_d`5=xz zF({Qw3=T!>c{4b~88SAmni+7XSxbQ0Gsa z(~y#yS|Qbo0FkP&FvG4np5m%K@r}efU9A^+J*}xt95!dF@rJqIyZ%n4GxvQMAH0I)tGEBr#`>u5xpiz47Mi8c`Xso6pkP<$P#?Gsk7*=7yfd$Xb&g{YlYH}9M zsqBVD%VKyCC93D7#IzyirsS1=m(_4uKi=G^>t@;`#cp$+!2T81oO}5)YM4)tjXq;; z<7R+LsZf#hmUh0Z5$dxgfBT3}XRxn&_&0Og*XWBFSLM%Mya(tE6pLfg%M=*|UJwqL zrF9?RgB5kZu-=VwMO*9dqrpi_L=~F1+dS~@hJC;7hXLV^|)zJ5L~$ssq$?! z4~i5`uLtvWAt&1gN16#E3;$~yzrUAE!fcj;YBndbj|KoaHix*he67q=J14J#J_mzk zGswIL#91l^uNvaqIb;%cm;liuQZ3kGh+KAlC;Of|sL_2m zSs2R9M3pP_TPx#KyBjgYl`wt}67y!F`D_5YJ2k+37zA88f%5r;;emU5;^uV`PP!RA zyUGJ~P8Ur9a$&GIV_>Es6%ZJ*gEEM|#X(-e46qQ8hmh_p)oi+>!(Emg`+YMw2CTK@ zPI&xbcaD}qW8qMTD~}VJnafWd&(Zbl>l&T%2k3XtEw8SPGRf8M+w6NI^TVn2^8CSx zeaE9q@ML=MZC+5$sgMRQxN$2NgzhaHK`~`ShP#A3L@FRGM;48G7*tevFV^_RiK`2q z!V`PKeRZV-_6@q?qPPR^-u}pz?9u#DgI zFI#HY*K)YvEg-m1lLDbsb41Dv7C})S6j`9!q5=e6Jw$z(A>0N{0fO=ZZQAlZZM*{KZ{0EInOl-(d2uy~#@hK8KKp#$Fx0C@wOzBY^C*R8OSkeYlSW zVuAIt%4#4^MCy_#jHCTMoB^z;fL3p6)UX<1DrkN_@gt6(?~)oPNMDMK4rqFnUHKH} z@@doxewA3!kHh5<^FRXzRrxZZx6Go5%Zz^&Z1n@^Daa)yPl&#x;wb~2^XpK9mFo;} zDsGBLIB~S1bY|_35KWRNFo`XV?bz(NQrSP?rPe2AXn@vGYeT{?zWd3(l2Gh~^0et569NBhkQsUC^GzR1m$P zY9{UHf0uSeI<}8Jk%(7PbB<#h0$R~>iNFO0V~H$G z6}j|Cq*}xvP6E`_0tz}Ccgvrb{~~SGuwh}CadHk|#RQ%V&$x3P#x#qLM=7WvUz$_g z$-)?SJO4r*?Jf|6`y~Y1Sj%?V!m7QUu3*#H9;;}iKnEUC3WP%3h&EoJP(31p znx95gIr)`L^%x#<;LvYAh7vxsXEsQE)L8<|>iDNfR;7?$Rc7t(OK7`JAIRB!Zlh9k zvOxeMVW%vLwS}W70NhbX1OTHiH(5|OsvaQDl5tXg9x|U=3zguD%`p6q#mh|R>#qOG zjiT|QC3t(|#QlWS2Z&AJHCA8jaZgW7Z(nM!puX0gE3+2UV%g!61$9I?BL)h ziV7-VI>r@7b07z;!0il`K6)&DtJPcoojAJ#cyeq~?Q#IJH^3+bHR1+(OLLFssn|(J z-M7+&H>VMH1t9Pr)ZiYGx7Y+8apkU&h&ZKXv%N47dDws(Bnr_u0etZgi;^;oDa-;> zmmBTb*3;u9yuW2MDmClZWhA0&8r3wT#jeXq@)In^;>kTIjhi!;ZW_z0RrM0U{>KcJ z&Jw(^2ojZx{tHe+CB}5j%Al|lG~8P=Y;Y>6gATZh_|t)7aN%zb_eZ5{*5&}9S0k>w z@%(NusjSqS6S4`6$Ns9mW}+uWb>D@JmNAFaN2TpFSSqk_=NEnn<$fRGGi@B~4$x@0 zAZukTk=UnyJK`MNm_|Iu49H?;G$_Ua=KTy6g<7w;T@WeJ-e`sv6xgN`_##B9*bN;6s=Sz8wH;n6qENL< zPjpTw_CRUUAEAIQuS4I8e#b5cC3uSwkDygc8MBoG8uz6V{q7}Q!KNjGp8>wLgi*^E z%iqO3ysJ%~O>(uHdBe8`J-Mv?YyZf2(IffvRQtLn&A;_aHTWA`?1pKmchZzBOOsY$ zZ!wVh9D#yMF&#Ge7e;4YrnjJPyZZsyj2g^@j_Anis?{t~bI;9W?3eYTY*falMp~#7 zg4@udW2KmNT^eW<4qU&06S3IPDEUd#dOYz|Kne#8Se1U6IY`ZxzSm$G=R=2IkzKi; zT@wY%;-GL2rrCiIjf#(#NakRq;X^1Ps#Tvx?@UAZ=@GpBT_~fgIcwoBa62?XbBx%T z&jsuNi^A_&Q`ZAu4T-K#^1ClBZTI}7C=tZXKg^pbuUeY^O64TYBo(X$A!K3$=S@_y z2yUz-lzdS2BXz4V=l7uws_GVRArv3Pf2ipxJ$E)D`Bg@CJ$Uercce%|rJ=KrYV2%7 zYwQ^For1vMk^_qz@=z)ikc+6N962CSMRc9?U1KtppRP$+C;CgxidKYSqK{Jrn=`{E zyeP@CrAA4~xNszIsglLff8))afBh`&*1;oiCAz1nCfChpdSW`fn;<=1Dmx|4D zwY$4NREH!@z@dxLgd>Rm*_N1eTWZRV{XS^6wdrYo4%eObyx$wur7XqMd0%zB$KPC6 z-fDeM&MhCV+FZJx_I%Hd%SLwJ;&+^$a3{ETiECGD@~b5WNa)yyw68R_j@qnQ>Tr^< zRGB0~+AjeS!Df23U%-#LOGrv#0=+j__{9) zMgQH6ZkHn4s%P&>-MW(>A{zNxJYj!`KOuVPn#m;+*--3exv~VivDr=kwRf1R3uc?f zYZsmse4mC&G;Fafoq!v`k(rl`gkWR@FmBaa%u~VHk6Jwg;1IUs& z+>%}#E7Re%)?3_l(M$VR1Sgi6if))(nB~#fgqoc>QGmZM)i(BI^w_b|nh8amkx^NJ zE>I;j%7TRHb4-T6#dZaLl9fP?$TaDf9nwvSeASJgzLH=`KRYUp>&w1etaqJ+;pmz# zcCBr8Z`CjLrixGnMu91`3mxVyVsaCdiiw_w5Df;)uZ z?iSqLg1fuhJ7i|QnYnkqEAOrK7OOc;bywBys@mO$UDdz8Ve@kqHx+e|Q*fuHHCshR z+TMtWa!IP6TLubKL(x7z%1Sr&fKnM*dw1nrd&f7~g0m}wOZQ#HW6~v##U;)M3;auT zJE|KB6&l{#`D&MCFEd4Ru;Kv*dSEK{PS(jTyI8(2Bk)FXS{^s;GsTB_n%0(!Vd3%GedO&m-I^pqJMHAsL3f$ca`wpRbC5~H-LKT1 zj!NiFfS9Jq5R)IAXDXwLPE3rIm&Fx}p~f%*4rBZ#54rQHVK4w>c~o1otC8&Do$cP0 z`50b+<9wKs{wcJ)f*Dse8bk{x_8GZgyV=E$#7>vAkQ{dVP4TUzn}|j?8d}2Y$LluM zgt_?Jmz%Lu!26Qql;^8H_m(@Daj{J~R&#z3No|TtZKfhxUP>ygt7ift_g<}iU!s|s z&hqivo_RT0$29P4Qns&W^79>O-L7#6ed1`z($&=Hj5$(REMA_}PCp;l2__x~nO5Xr z>tJ_OEN9IYE1K7ibfkWIiuVLAh z_Cqa}sQzjH%%(9y57=Qd#B8^?%eaN}=d-IB4P zghI$*>>{~yC5o64{9&f$6eK}kFe&K+bdG|gROp^st+z&K7)`a=CIZHU5qVlrC#!YH zy9x=2+g{jE1a>f8Hr0DD)PoUtvyKp{vl)n~;CR3%-y3?Pm;+}B&SO3!DKwaN7Vd4* z5p!u!fbrgBnYAH@Eewy25Q?y+54hK==ZZ5NUW+8@A{T%iiKtni`!Op!Q&4>=QS^k|B~I}Y(oP_f3qaw(Ixm4H#l(Mku;(rtu4lAeB^y*+>ugw+Bt_neyX(E z?E0bJt|yc`SWx9INNVb2SxL=j&yg(Q#%dL7#*MY#D%(c6Bg*oVW{EbPyjpRQo_Mgw zge_i^R9ywk467_2h+a#(rv0AQAmEjQWS|*F9yUzjfzqRNZ7Oco5RP=Dlo30Y>v&%& zmS}Qd|6`3&DgO@;g}@IW41q)0;yuP)sY@KnG^+EJ_5>f|F9$nh%DnKRetGZQVc!z7dP<(qv9Jz8q1&}7r-L|t;q}beI_)tR+BBaHm6)xwOf>Vb^VFYSqRHroU4m|eP z{fT>8DOvXHk3KTxV~cjiRx0+VVS_6tWwdsviTvpXCFZPN)p$N^cKl9O^SS-@(Mko( zoF@7&hIwmQXkhBK9hKxC<%k5TkGD{1KVIZ9dDxFub0)-PnxOaIoJr0MW-@Ec21Z`M zL0~23h{07sxQ??fK}{f z{M4cIb=08Mr@?-if%Mj=m0g#I*JQ`r=^Cg_2VT0X{o_zRT4W~QcIh;1`{&YBHza2eGVAB|* zkgnA*VyBU=VF*<^CknM*;P#2=rWxW2jbt65W@Ft*v+4-{8XpzL!_2quuAv&u=dv`e z>Sk<4H+}u0QI1{yf}S272GgGE+PZe6M&c&AoZf~tfkiAMj|rbWiqjdwf_o7bhb|lv zb(_VSuvRw!d%BfwB*;=>$Hkr|(@nKX&}ZJ#bz|6YAssyCBXCjF8`t6$rgE*VTPD=4 zxQ=1+`eDjrZLv}dsw#Aoc+D*+5)wl2%d$wt)V%SF?c5-D1+5VGSCE7L_mib6F$+5R z3t&9Yk_;N<8!RGA>X?~}1D0X6ehL+~xJ&3^v)-6vA#B0nfj@+l4XFnP$jLXyxn!h} zg%gvu4f)@#Bu~IzeiOU*I1M!-t@1aN9ivFd-;9(0fubx-m3hehAWG!Y$ELK_+jtY5 zZBq}y_|~k$~UgMQ1Q@}D@8LbdDJVD7`zx;kdGGy-D^@t zc3*vI3L}g#uB_NH&SGcu?Y_hsinc>PnkFE!eT=#)i(e;cZ!|?mB}9~32;xSUaXx?; zSfpHyu6^*XlHzrKj9lp%HY7Q)d2e%Ne#PY`y~>{-zzCZV3qhVj)YI3@g&RpYog-#1 zcL@^rGmW%!+quC``cpyb8d+U(J5!A(oW^H^!BSYLn8?ie7&$!xwV$a}(6R0*@%wR- z-Y1&!YN}P=jXq;-H@Ub~c;ig{#B({wy9mpj)iBL?s9Y9Hk2pZESf>(;HS9r|?aJN^ zIY}MX9p>;X^b0^jO(b?vXEwUa@%&)60tI|>vU z6X;h?sP9q4ZOE~Vn)S+@D$5MAxQ4Um&-3v^LVUDTUYuuV9vv-R(!66`gjcFUqlw)} z&Y2VJouW7AE5U1XG_7eD#ySi55b}_~5YLc_a&v9hqS^CI-Q=t}r%^M>C}JiSFb*WI zxI_MKzP3kDYp0&wume}b_-4b=u;VPd44ac%K0wN2Hos}MS=)J8zJOvW!9`RLS!A6z za77M1P>ybW$KUT9=AFUIgao(Ck7UL7=rJTu`=WEfjjEd_(byLO$S}%nyTZXw8V(5`?#=3)rcv)g!27k^tsXg039olF9VT_Hr{1 z&`}O>c#ZbsI!||4E3K9D9{TrOQ`?3rww%yUX@Z_HAuwMoNUZq>Sf?gN7wAwwhmlC* zCm^S=fl5~`{!kMm5*_SN+LL-Io)eh(s<9Hj4|-wCMyz%v~r*HV;|*Uo4p+Ots4W)7^D1dUjMkjnj# z(5vX9Ix{UMcKJ|ep8bwlmUTRSc1x+=oZ37>2JZggdHoA*0MkS2w7L#i&bou7LqFcl zg9SPLI<_Jv@AM`Pz0eUTZRlLsQP^6k05upsBy~TVx;bOPH(QWXPeF1Af~6l9wtPiJ z?!W==ra#;jll@&GR|~R@r}2DA6!+wj6~W;%>;pb2j^QU-3tUgr!R9u2stPjBX0Lm^ zYO-Kmf~rnFmM3BL%RyW!=4A%OQ+~)5)uyVP$*KaL0+GE%gCA!l=QS%v^_)d7Cddu0 zse{xfh}-qftyL!syx>7y{hS7gVbqE~3vW*!?wLoJb{xdbR;Uabl{+8kuJQ#r~`BI6&I zslTm>{wDyhlq991nU#@)w2_Ovjg_9Ytb&x{|J_n`dbZ!Ftp8f74p_yk;H2;9W@|+I zUm%s4>HfB6`fbhnKiMfJ^snXgzcXbG^#GJu0G-uAgPHDay|%p8pLUBI0(i7$j&9Uq zf0_WWgN|0wM#rK!{8yao|43MYf&Op8!-}$%)&X7ftyZGc^*!&T*ze;k{ca}j!& zdBjVL0YM&T(zQjdY9)IuFa}Er@mZ^I3!u2&E<1*$(Ka&_MiS6M-gR&QXcfIajW$I- z6sTe^$YIRJRN;?~ACTwJs=_J&6G07^I6AALhkD{o|C=HO`WM#gVwqi;kG=qg)VOCzf{ zlrS9+4=tbsMH^9ZAt^mu+CMVU3aJ2=zynsMzxDi|TwXwL{!+#MS8oIIzMb*bxeR}< zRHs$Zpr>co0IaCj`rDv;%lrHF{B5B=;1Y}+e<7RSaKryS*_i2ZI?yQpJzA@y&mFjZksyj4egq5}o z6}O9RsynRYUs`Q^R7U+qp5lC=;#P7w%Dubdanibbc@io1F^8N<2%1`RPP1)Klrl2n zvjgsU-F1vNp^H=})W?0StSFZo>%*7Sy+*F_^7riCZO7|=qlJa5kJxg0zPmp-b1Gjw zx9UklcIy1vXyJROb&QC=R6X#IMY!Dh9Ci~A(R}6+U^?FG=GMp^gXNtHzMmto5p=oI zXjP9$i^!%LoBwcp63z2u%N|o7DE6Xdqa$iF0wbfx3m#S(OeH__;T zUbVZYnK?$^j0ATn7JIg9AQ4aK}Bh})NGt8kRBMd=Wvu#G7OP`lQf4> z3mxk(iTFyusIH=H9ss@3Sv480wq%SU*9{`So8sj3*+_&sccfwmSeUe8={t~!vot1# zSQKn{RJ>*{gLUs*2}*8a zTp6Z=xFxz3sw{@TMjlnkV~%Eg-a)SU?lHWgx1WI$YubMsfQy|tz@CuQBQ7|RJk!8~ z4ej2tBBo~6$~*!aO7rc*N9xvId&n3OG@EpI%+RRAF!o-8Zd9;2H@+Sl~ zhtPv7MJP1$U*t9+lhsD7++sO#Bc5W+P4Ea};NF~C`ZQmc&7M}HsN*#Z%fAVcJ1fiC zV!?^k>!>!xbLl!_=$#>_hWo()?&urOtdZ&>7a3GFiL~$PS$v-4`zapD+$b(pU2W|) zIWqy+A*hsWmdDc=S70!7Sw}7L#SiLT%J^SI@Xa--m|7~Z8FQ@YR8?frrzluGsO#0Z zt+iH^i%Qt33g)M%Tp|L)&Bv++1wWRB%T`e*uYe3O%mwQZ`5d&a_XO>J&qP%q>i0L9 z?HJk#j9phPRGQuiAvocPsOYl*|5#!B1J*@o{x~apb># z9;a&B0gM!)K@hhYy)EC+z5}M-Laq?qICzj;SddyPtj*B61Bj+_#Y19KDFJC;IigrMqj3CpO>dYHMzGhJsg|zIAzW@HIr0xf!T;r?+ ze^i`PT+<=rvdE+v3lphYgBc9bQOn9l=k*RyH{2K)wk)YF?e4&6RN!=Mcrdo)O@ylV z)jWwzsog_AOt<3r#|&DOd6>oEsAr7w#jIw!3u=6xZTS{gTj-y1V3aIa*B691H|BH~CTluF?0 zPM#r}C!8F&Rqlwxr4RVvcLjf2?_KM7*n75s-Nkg?D=_oap#{A`$1*6<|D`hb$%!b# zGR(GO;#2ZFpIG7)N?j5MaF(21)dgeGTIQbb#@;BGC6k`%_wWrxObT6B1oLeZvGbrT zfvu3@n`Lq`lh+?KC_d-KI%?7Q_x8K(^^&I@6zbsOETuc8u_NJa_Z@({EB$2n*>F#n z>?our@K}R*Q4(xc{({_7>ta@Tg?SuTFN>tx*p$waMN8u)qI98W9@FY5^g`I!c?gyU z@dHQ$h}hT5SBnJ)!V+z>RncfFib2`Ef3qkH7;ZE#VX7!m(0`GW=^F`<_PC8-n?UY` z*>{tI#p#l@u|hdf;)nz34tY$))td9Zy|4-A+SCjBQ{rp1hU=bzTwKD!CM**##9cON z(#l=64sRz=B{G?OfDUjTsH#nvdmz;|oCFZ*G`~duu4&z(^kroM@u8#Utb)up?}<8W z&H??lhe&jrb8O--_cj}8HgX>xq>C70w8g8Zq5ExPzqfpn3Po}cmu!b9+q^V!jJg>D znjNv``w-Q6?_yvhd8L3Hx0Y4=38NPb1;j~(RL7PsVW;7dKFH{t40{9` zzJQ9vKfmGC{|Mr4@OCbmSy)BS+6WNV6U@~s)tOoc^ELA#yLIqDhj(wX75xWY7(GT^ z9?J6DRl3p9!&SuUsIDDP?{(VmnVm}pHzqg58v1t}nGngo%j1_ecB7-V zI#5`9H9vY$HyVXU{GvXJ1Z3K$b*L!e0iA!Q=dH8*(QEdiy=MQFdQ3vgg!5uCt}+qd zEUnKuP@2?0loO5vz613Oe$DXMnW5|}!o!tOmFdR~ zyYs2x+kKT|23Ig6>2>UnT#s5ipEf->X}2NS2or!G+0gJu-SfJ)K#v2$DYMw4T<3k* zPNt(2Y!3a4>k|lz5w5t45o)}${I(s6OHwooQ9`eDZc#6i(s#3> zI6g=ox%9gn0IT{hM zs)>6{2>U2Pb=}hMRv0igUBI)$^%+|ny*lpN@3bwjgET>>&>@c@^qN4y1LG=jnpvw5 z$-OZ;hIm#VM_c0ZE_{(Vyf3A8VVu@6b(FB5^h`|@Ve~=JW7sI|)ZyYxO_)o77Q@Rd zYLY22za4rhBTvbl;5pWB*R*fyVQ`N=molbLRV6xQBB6H^uW)MA9MkFD#ERhkgGL7r z9}BgMGsu`g#G2<7ruhuP){QkFAdeEp=AEgyM_sf{$a5h~rB;zG`4}N}xxkCOL^ z&9!6KhT%sehrop4g|`0~`EfdyVc0D#^jcpJRPvrs>40=%1?m+Oxz6r#ag9{SOMEWJ z0(#YTzPbHk)^`c5Bo>8iplR3Mi$Er_Aw3V2 z>wW;r1B0bBpHQujtoIhQCzw+JVWT)0GvQXwp{nm){QWeXRxRk~rr^kLgo^oi*@6}8 zxzbxWUQqY*D(eR6MZ%Q8K@s)cWuBSItJlhPfy)9v>_th(e`=(12}pr2-5z={0VqZ*bzh@W{l@%>;B7wv4YouVb7 zhHZgAgmj|PSPo{x&i1_FZNoA=__D&}48`C=?#;0=FIl>xKRB9|!z_^n&iNwwlew3&Ac<6NW7bS`}rsen@6Bq4* zZqEksihE@;uaN&`b?ReAQo(J%1L-O`!?n>9%^A%}ALw*SXG$%DyPrJREq<(sXZhD%R4SRz-dc#&4?JL67iQao)rJ*Sq9KL(Y4X=@4RszSOm z#ng!ceMiEl$-$4}EATEq9Cec>CYm>!Ve3Z!-0RqGI=KA)B}kJ|V^u7*@6=R9c8J6e z_7%d^xB6mo`f%U*fW5;9sLXc-=newqUZO4h@qKTcaW@&a6rqq`VReg>ND0A+8TB^> z^{^eWMu%@ZT)d)cQ*`B~PX6sh*|RE4HkBnayO~SsY}`s)vI@dYu@ve`r?lThR~>!4 zOGwB|zu{G*kgF8SXQ;#{)CLN_DpRJsG;6f4-`0#?jhT+b*=uOM{G9#y)2Y#3?gXpR z-rAZ%W!5M}otU@wX1spi?E$oyCN{`e;w#ffZu*~-n(~u$8)D4Ns%jCbRA%kl7CSDw z&mxkmHgbo(QtNu+588&S*@BAP&7JDg*mdCxG4CjYf-G*%K7ETMLL?^EKzweNxZ9@{ zze@V#38q#N7#1UQ)U*sv*s6%m^^hk*+eY@j!3eoayTE~Zg z2I1#jr1MFblHIk=dFv{sLkWLvr14~IhnBi?-IVZDVRQP)XSIiL&3cn>npi0SOzb-) zr36`ir37ADop0ZVFL&>spT4P*H9m!%Xnd|?U!5Ll-c4mR*-CNqHtU{u;ALxkEj!8> zk_oJ?mdS{J*VlH}SHInnL>TN-)wmsOP`(#d`Iz&nl1c5t^XHFG9Re@=)%2asL&B32 z^K&)N_GgKDrJBQ|y2u-yc`FEJIZ~0>ui&HDKkFy0QVJ$`7p%aa5RU339EcXI4^6R5 zB~6j8#VL>K{H4W|D=aireC7;r=m}AeqcAl*+#w#C>Utg{Od^C~C{YvFmE_F7AMG#P z*api@P0cM$p&g$dEL3K>OLYr6b;dfi;&6V=we|m5z@uR8k;vfWEQOcso5BGE3 zXGMX-q9hJe2xbN3Q?QyD{v}g1ZrG+%7K2yXR{n!74y|bfS6FU(1|Yd{xtcn8gkA() z2rdfvGX60T)CqxaK=BKu&=lY<#3Hx4Kf9w1WZ@RQl1EO9qF4P<(85nU&{zHac)Tw| zpY3hv2!KJtYBw0`Z6FSNv0O>=&crzYU$x|1DPXwZj({9b*p^ z2oQ7=QJNn+@~; z#t49p!VJ)f`ybc)yY0+xY!pDRG68hp-ag;d+uo=y%x^XUXee*mbHD0l0BG0&_SqTV z>H{!N00GFi^WTm!0eXz-P3`UNT)?q6=`vOT_vBYTzalUjqPt){}OKp zwBf%WsVt263;>wR--q@e0s4O&+JH-C0H9L-p5u?0^*`kR^d$qJ4ga3ukD%~BWng~m z?EjGAmyN$W{$HI(M3|pa5Fk{kZ*TUe<1qd{&i{0r|D;g)rrrmz=r59nOicfZZ@&e$ z|LQl4fUbNy`CqdcfA|gan=m9`s^kCn#=rpJ>HIJ2Wuyc6F!P(f-~XGvOn@Qtw=&-R z7BG_ExIS;`Z~n`|02m~Hsf!8FeQbccC=1i?b_0|Tf0Y5?6)`ctF@gTHi48zJdOP;l zw7=E&yZuZ6zh?&cA`_slU!MT2!#5_;uXEpg6fo|7l>?~vZJ!k&llgWYGXtQmw@*Mh zjDULu;~U|K@hu%t7QklKw`=*uG5QbJ`Fp+pWXu0Hjp6U}a=!#k-v&3p8w3U4hPNR= zUh+S9XF3i=O^><<7rzsQ~mYY5?*I@Ff87T%o6<|GRSMuMYp4YA1jP z_SS!Ib69_%aGr%|KHDU0ltdRGyV%l#RL%V{2Pwyr-zxY zqVViZagzoq6_f@f)Hsd+h+z!+0{`CoFCU?SK}gmRl{+KCsVH)Ni$K9-WfhUt0)Rir za^Or?h@(4!;eeqbVkOS zax&#Gi(mDTT{?1SU8#X3&jjfqJVn=Lc#Pv?%qhhX(m(7UK=LAOF6Z*KW&LQemmI5c za^_jz$Q)zxA?Ey?x_*^&XGcffiUjkCKyH@RKokM*dPWdR=EJe7{{u(3u)uS%9d*b- zBL0f~5f0Mn{$uye%@*#*vMfjtvhE|E+sM2!5z z+|QCi$tWyvr(hy1T|S+I_G0rs(7CO}(K!s5x9p?*zewwkD~{ ze(mwe4KSuiswwHiP+H-p3fY}XzC-g3Rn^l-`9jO@oJjxJ>T}gU|Cu?YY35(#ENL>VYxZikD zV2O^!C!gX$oe4Q)1Cw5W>V2P~6}!aA1gZsAErL^ayYIPl0dn|+kh*aBxQ;37@rQQ@ zV~F<~%JkY?#ED-hFrr1bXq!ZRWO<7-S>#JfzR4^;A7zqfAnvJu6_}!{qbyEinQX3! zikz@}2>ybS{zLUV4e|?xosh@?YE?T`jLe|Yg>Y$R9p6%R{hY@^{eJT`XfIwk`>bur z!}P&HUy06l?=kNgZ-gcVwCh57T#+ka(;kXNX}qi(nLS31{s;eu=Fsd7k{Sm7VMLgo zunnp6j62*`qU$9A=Y-br16Mb+Ub7%iO&Xy?kF#bK+~~}K?hBKVadlIinpLwgGvHEz zr4lcIZcp)p(Zja8k5`ekfpJwtNjQHmra}5S>85CPD*GT6eS5XBDuUaKJ;(9Y?u;UL z9fzzI{PHzlT!Ai8;w1Fmv&eAg68eM-fgQ?ofSTBQ@f?(`6RHa#9lP`f?VtD}VHo-a zuAit7!+N045#4=x#9*olhp^ej;FEH<1?>ycNLe>rs(%vm#y)P#iLIzg&Q8`2)$%OL zS|vM^KG4afe&Y^^(aI{FxiQ5vT{T}d6Q#F^xZZgn@(O*ad1+~r^BHTHZ2)bj3_ljh zKhLlmWHXXr?6fqmW42+QONOAHI?&zLs4hh)-ONCoP|V}E#|wP!CsFku*;ZeW%_NEZ zn4L0C{*GIwj|;Zz8=EwDjrp*o)@ZP0gdtKZu)|kxZlISCeVAG_n@J`G^NK|}b^i0> z?~^)7Dw8~NRA2YTEL<>chKST5ESPkx6EuWm7Rj0i2rkqje$45^dBJ(L2cw2A{Qy%Z zjSQvP@Sc$Sl#5`L#v;Zgw0wjjk0zHBbr*vV%$*gLle(9~o5ScFCO9K`&GFz>A%k*7 zWbDZ8MWCI9)KwAH(PUO3(yeE-Be04`Qs>U9pDxwyZV3Wo-`p6?0*%BeAzIzc6X>1i zGf7~;$n=erYQKJF^D6%#$yt;Wi4wLXd{%ckBEO_Uzbz=yQZUVcRX1O>JJHZUX?IE% zQ~0*~fVu+oruxSJruD|v9ioL)D2R<9(Lh+yHy7*p$7$|WNV30^E6TG5?@Vq{Y#ZA7 zM`1$)Zfs@}tjmbnUXe{^gL*f1kw*e`*a#j-t4I+9kx7p$?&ptO$*Cmq{Kxn7>Bel+&Gi{H~p?7COJob>4(FwmC zA#25CyvrgJ9VAmdX5t9@bH@xs z<&bS7>xOLsh;gZTnE7CPl z$xTk?bD@zJss-5=^0FeQTP^xJ__b_Vg(Ny&P9%MC!GwCQsseT$!Fes!Ltvgg-;z&{ zV!h+Bk>n;%Pmc=QtP8=9eiKR0x9L$%I_B%eOx2tQA4)6n0%IHNba? zi|d|UN8&9Fp}p^ETk&fdFp%^>yA^OUs?BkTa}X6ZF_u+xqz1DfKsHU&lqbP-L8HLO zx;>F68Bl-_07s1VxQ1sEKj}dPtBGIf76re6K)yLiNRC&GPx#~$&$~n;lnw-k zL4$7SG3{?=*p{cgL`a{EkoVL-fXEGS$Mq$ysD~GelfjL5c*K2%f_jm1Mj^hsNkBy= zAq96QB0+;YovHawkO1FO-x9Jqw{?^@99}i=KH8Bu6JZBhdl&#AGPhM6O);9?25KRq zTp={zmGvHYRSb`a{1ag1=6U8sdXb|cDRQ?=43LU0vaz8iK1F>4Qyokpqfdueh}2EO z%cpVQtz6MjX^fMCWb#U0BnUMbb49rOY+HP8?&!o`3jJ+;X#xWm6r0Qx`bGg~F`AHT zKixYrJOj>_B1sKcA9+NXvovVl2tFb@FTQM~+lenf@b8xj(7+ApcNK%|G2wR7_OsJ4 zZ#E1~FGMy3g>!vLYj<=$S!(*P7&LYe<-GTTAil++s~Mkbu9?SKY6CavNqdrJ zcC#iM$FG-_jJFmeF{eP2a1)f$i$tD<-y^>>p~%NY8PAFbymxv5QrV-z=@XU{7faKx zpy$?=OmT#lA{oPISr+d{vv1PZoPokC*|eCCxizC;wE8(aKYzkxd%F`TA#sQJ@j@a@ zGFWAPN|fkPKTeW$V0Zg6pSU$l5J_FnCL<2LKUE_@IvhnS>wBzwB5{}+=-`w7Y*uz) zs=l3bijpjPyuc3XEfs}DNK2QLtP(rljna3B2vW!4`5zMNV}>XXovQdt?IqNiaX ze!>n^J`|=JL3)j9LQv+XjmG*WmD}8(svLG3KjKvr5MLBblJ`jlMrmf{18?9H_K=Er zqD`1{KW3va0rJvxu9L}qdany^3vP=O4Gjxg=0XqI z4?ISrOMTFgawvBt*)+2#rIJGpk^vS33KKza1$L3az&QmeEvn%lC(6(zL+BOKn23ts z0(md2sVujHCoqT43%cGHK~QHkLI`6PaAua*m;KzQYCNu3!^@wkizmzm=XA>t7&V<) z;AJi66i>vLMQ!$YCJyMEj41mszJ49py6C;Z_thP{!k)NYwfHK?rdC;H($gSDO`S=w zzQ#Gvn)R!B4-wweS5Oy}DWg%HR61<^|wKNfAT1A6x~GsJCJ9teSCKSPj+5hd&VlpTrQE->xGO^4~!R(7R_Jfw>Ue0`v!0CGU_&RTe>Szz;rf&bl1 z@|-|CcOYGwwmT$xFuf|+&z_6y=Q^&POeVFgWktyG|D=a5=)iUM)|V|iKz&ek9pJcPeq8A9GgP29(@$~<`dI9vaI+fGkw^Sa-n zEB{{4Ys7X=?A=`|rB*Oakf|w^`5vzOJ12O0G(H&w1>R?%YyZNZV-09m^j9`WljC?e zr0~?~4;~c7a647Ju9=ZpVd%3wc9e_miaNoS^P-Z|4JUEbS6*FovkSqnh|S?n_TQj0 z1qlf#(zy!4&stW$zMS%T8-CBFhxD;IsOODQa}GQA`VZBDzgPeioyyIqRJ%()Z?(4%9W@uy$aG>?jpbmGhO38?|GE ziir*`QJv#l=7+|x3~(=^yvz^oUs1C&mGiVku47|UJP zQ<#LPJiRBG4rkBrM`zZU2W5vWe5m87PL@u`{ivl~FHja&oR^>;VKdz;IjvSU^qF-k z8ubgDBM~>%doHP8xoamYjao7UJjkPvPQ$Xjrp5B<%eXy65`-Vk@o;jEfKqPtpO+;F zWlwcnb+(;~xWk-+&xO1gub3U1y`y&oZ_us$DP?&n$KPjDTq|_h%?FVP&AM`tF88PLMHtDE))xYNV_GLS`KAQ#?e>jAEP|11<=^j5cUw#jVB2jkaBfC~)L3*?R z;=<>-&o3aeEBb>I8HJ`^uus9KW{nR1GA zDbRwwo;U~R!a8)sbFc6tCM^Rt{YbN-))*;Fi|7%(XQhhz0*`<)$Oc(=@qf;0k8LYr zwJ+MiK5Gvud+Nzn1$8i#L&n`hT^#`LfewY)HndP#M5L94@5aeo#~p%aQe3JGcCvXv z=dsne`=*H=`fgtUJ)KE>rO2qchY{BXD}#?ZROq3?#~Z&cu0du(y7JJ)JEN*Vxx;Ja z<_>Ri@lCvJ^d->oKL!zgq0q%Tb0ee0{yBO-*`4iUU;`h8wJ@DRz^FULI6A7Zog~ls zj61(h<-sVJ`e_2Tnx?jrYgzze21C2e?_WrUU|0y^77=f2!Eyd-Vx;s@tq@H$0}rpidKljEGJXc-W63&9OoD5 zWmwJt?z`zQF|2S~ioI1o*SrYO9&5)c=yk*`FUX^JiH9MMQHLrl{4Mp}9`3aoI-%WT zo}_EXX-8{knQ2f|B6nIq>dqHV6t!dYj)(j!1t!LB?&UToL68_U2)kA+P@ z!9e|P(ALAnb!$4%pNxIBxOT^1X<9q(H+Awyae$VKJf-`w+=A|s%uIP``3c7`v+vuH z;nImmvrpJMc0E!*INvnxVUP;ZXTCa~Bc1v4Eb+i)PRe^Td8%zYRKM=YZ`+(IyyV%Q zBBL0sraY_Mq%Zh@dnu=1-tc8WIZ|g{CTM1R5e?T3!eYYxX!Kpq)r@z;yLf_JLh^sU zHn~f@#5fV&m4ZKVsc`A(*s(^_IL_pEAzXp=P*XIOfmxV!usmw?SbQ~msy~T&?af$R z?P-7vnCxr#GHi3015Rj9`%>C4z48ojWVHF*?%VxWCfvnc!7m5W3$Q~7jnBIe`7z!d z`5Q?W4n7uKlc$hjN%S}o zy3wrs&~`<8P}%$3-%owJ$$M0tqJIhoCHZqFyWSdP91^?9t+ zaXj4(QazuCh?>%64E|bj`hHaFi7Xyxz(wK0=4n)PnV_$kDekn;wVh$9h`Ydgp4%QR zOYD@-jL+njbB691>_9u)b+^cdfs{O}T}<#!L-k5s9sL@W`YMZ8PS7-DCO&b`Wnyze z%QPnVG&*$>WTjl-k)pTlfy>3mGiib0NLt~VeUeo6!pT?b*s>hbhV{qpK+im^V;fxK z?Gf6wm8^^?KGGf3-Okf(`i=GNibGR#->Q7|uIS1XZT`>|%Qx;_X;hCoIjrkx<*E|; z$avyu)ZXo@K+o)Gn~fE@bC)`d6V?W2K0($}zI$+XN9vst-qjQgMsjW1d_VirXAvok zyH5v^=UVyI`Ba6E%QPPvqzUymGBG{In*mVw@_ zOceN`m)MK~S(LoHVSV7J>5*N1K4R6RnuQ>Hw%j-{&UvA{o|z*{FFy4~3ZFm&;&LV) zpMa+!Ijd*A_L7lfRt}~=$)DD_jyc_#<+q{dS(JC;WusD@o$`nNzA!!qH=d4R${N+O z^Kp$dly#{a0MKdo@OODP66;fF8RYtdhs-H}08)@}aCSYV`{upR;;UcZrNxWh@4Ua3?7!xX{G?9h z$PBWEu`U4m^_-RO**$z_p+5r5HKi^BY%--ls7p%b3t;Ca9Bk4fLo^a5p*b2GO+p56 zP~jEEUbARrOAMd;{^P|pAm#Dp9Xk!vC^ezqRU%qUt`1T33avc+d?8$ibDEsa&NGt7 zHFwq%$*IKnd50wA=1+?#yG_nzdxJ4wAItJEZJ&@9ZYq@K-+vcXEZ+}X$r<*K%VZ78y?1cBqYxQ;;d+PE*OGLt_=>WhohlGjR1 za})iZP(8Q(L(yFZFDTZ~SP%~Hh!>XQJ1P(6(U%*C$T3B&^~i1L!sRJ8(nTrXPpm$( z7|nc~cG4~2H*{Zb&7+9)2kVpO=Su?f5v!t82BbUgu-4CB@W+Cf9kOjA`HLkE zuDoB`Vnc^%qW4K9_?|;%o0;YS|7Rx^ahE4Dqn>N5xty^wgpqh8PHI~4UN8@KdnaH? zAf#K31Y0fjXQ>k$+(V$Ko#H9vEhW1{D8CV4yI=ODw4Q`aYI zxa*&JPvs|$am?Tzhhgz1ZTyWQG*4F+WOH$RJQgU-dauKnpv#6n5vR7E@n%#c-|aZj zE^A<}tnt^%P6szJaXyEqdQ;ls(Txu5a(R43;(7L0Xdi4IBlr1g zh2rBM=PA0mQR85fJ9|`)4Ue@;njqst1LxJOv-ePnR`|MsgITWUt>Bbl^Ar=`j^F~< zQ^~XH($SXoY~3FfnRoIS-?x1F60G%*BDt!kWuQYFE7GRZIPQ@M^H_Pp0W(p(+A1`e z^VNktDQo@Ia8&elrkV4)71xTWx9&kxr8S@O0ymFf~ZU5Pez=cDv6JUW-q? zD>hmNKD~#&t1oo(NgS(ps=3FvS^k-7GN0REGBjo|LcC~SUa*hbDsfI0+wzK*=i7IR zIWh1~uQPxgQ+0iu$CInQcs!yl{O@t7+R4A!Br5nROU-SzwD6U~rC!B6!+~0HZ|Nt6 zfk&R2v_rL=w8d;)p><_ziHu-Cy6}6L_GoWBEFJZ&Y-c@akUocNGTRWXLv4PS+*`68 zb_u`G$q2HP*@UGrrFn!gkNT3$^F#y1W2AMx)60EZ(j46G&mq>;fV>w~%$n3@QfWI(@mq>se-rPJLZPC_XCTth94sh zmx&eeo-RbwJ9oU%J(o_=XY6&LaqN9+zSDOn{A?(W&~&h>rvc=k~@@+ocyIOpEoQ;wZ>C+3Y;Z-ASU-g)>+t^^XlIiDzVTzfL5Zc>ukJ3WE-CMFI zt|DD(=v!qvoF1=4l~gn)(S&{WiS)Ez#ipc~1AgMYdRNk_(3+2S)LQDm#c=J7X+gcU ztKP#j<__Ps<-kOBb+XiY_^ogySt@JvK)ML-+Hpm8A!~;A^MyM)*pjTn?O^Htr3%OLcDqRnY$UD!}cYd_UV<6-U zDZ6t>w>^V$HzDLMVSAK8;ru%@R{ve&ymVX3#Htj_C0Cp-Z8PsRk{|6Zz*t1>AmBA~ z*z8*_Po)J9^bjq(inN=p;tSII(1ZK?4O6CqwYlvpX9v> z29Kac4ZTNL(`fHXd7lF7$wu#aX-^u5ys)gavqvchPjqRJx=&V@8eK+@r#(js+$+dK zcGF;(FvlFQIHnBJUXI$Rp(avsioCw|oog6Tf-e^>`bIchk1Be@WuD$0Rm|R_u4g<8 zm^8Af)T`&($mrvx^_)H}KYLU9*w~$m2DuAXg=Hw&r0~Zm2imKZX+HW&=+aiaTBf~J zdqiR>JK!z~&Bv6WrG|*T27DT$%kz;gm<%akNk)tW4 zjPIgpO;=i5<>WM>bPq)fXYs~f*dLd4$vpXZL>x#%gHJvj>i~fZnhLZIlmtv&R0oJ9 z%gmw%rIU-+Ts1IM-yYMvM2v4xsRp6~7;ds$Ku383!8#PaSUFL2W@kr*qD-iP9z?24 zXq(cEqXKvy6kRqu!PJwOO(mzy$kv?&NM0kG8}0wF_vYbLe&7GFM3T(XU`U2C569u0 zV~mWE%ww4)nI#!AG)O386cJJ>k$E0UhKw09l_5i>LLp=5+4p_U{c(Jr@Adut{(Am; z-q-a$hnKbYUTg2Q*IuuE-|c;WxnWYNmgmVnwYj5VHT$NO=faz9dirH9vVZ0nNMU>< ztFRvQJjjd9fRv#}m}G!7hIbhA*r)8+hw6#WYXvqs0W^1>?p2sfZJJmU&>y6ATgOdM zkCkpv+!kAA`u6L#$z0NDAEz5$aw?l$KHhqzT7tPAJQ-`@JDNm+#?5%6bUMI=TGVIbnmYG)aGo<&Vd8M+q9k}G@ zZ-#z%Y|~^yr^vY4q^4ix%Rpg>MEJ31-JTDx%s%+CkENG+iWu^bPmut%tpAWqao6HQ#e(F04R; z?(+GVwBFtZ?9&)$Q@w*^w3_1CKDp7DsBz__Ltiu$tA$nQZ&gr7on#d2r5=`I{7HyiH}fxN&!|nP1oYMLL2VQg{z zImB;qOCTxenaDmp#;Ed_GDR;im#BU)dc-9iahl9dVH8SX3?4hhWUBQyLD#>Gvp-rO z;rQT>C6}0`i5r18R0G50Kfg0=Ios6SYMQ;Sdn2JbqPnL#$#{ML!A4Z*vcS}ctLmcq zW!e#n$(An)RW=+`=#9Fq7&Kepqc_@O+wrgHMqQoG%}4TgpOHHlxny-`vgP%Aw58N< zlEKY&j|0E`M&w2U;!yOD$p)z%bx9)_+#Uv{E4hOYGFF}uUL97R%w=_wt4z1kkFeH{ z@ESrN`&7lSVTUMM%nn9a*GJPv+;IDTo6Eu-d>m(8A89m#J}6YH$9~_grKOR_ZieB% zMt%!Gzk#m^K{wl*TvV(kVbI4&BdKcq82Dhu<}-!RvdX!wy&u)Xf9(x9?+$*0zUppq zF|+24+%tea$W;Zg)`wKH5>tS3`Zv=Luo{fK(uF=qRS#h^nV^sNIy}FGKd($yQpQ(V zexZu53bPY2UbzK*@DmW1zEhbsQQA-7E_q)WHhWK0WK7U+;OnD@n;-@BVZ_=}lgA2uTyPgO3X`U^jQIBU;X9uz-}gT2xLswab=a9H zSw)p8`Rw0ARVmF(Rgs1Q8-9st(@Z~JO%FZH}4@IX!nImXU(7<9O-OBea5h zB}oSMXauj2SdbJu{c=tFXuOqe*SpWL!pH)cTrqI2dwzK9^v7<)A*%#-p9wV^SJ9%|C5leh)K~(grs-1;8dJBDNRfUy zeKLyF+rac#^WhD%QUe!q(>>}zkxx=fvDn7tpFW#UY}xY4H`}C`>gNitP*)4p7@BY# zsxjPBFsCj)Hrf`-kfSZI5?0spxa?Xg%dO#@sI6ybdMT>RPWO^k&7F2RSX_S4);PDv z#Z`+<>~W=30duJ*-A0?IWrs9b{XViP=hI!cvvtcnj~zR!;KHJ#W^wan=>?(W_?X+n zZ#jf+4S%}u^-Q++Sg?A+S(&|-nQ>=Qk4uIsUR-nZiS#|b%D(5X)j`4TaYl<^n*38Q z6b~+_`juP~Rvu+_6+M;MViU-F)gfr6Ww?j0pekJFk(y8a-@;YYFRp|`?A-0Q2MY`s z6@DGG2);1oI+8r!wy4#**(_b-_uzWz_0-h{rsot@81It&$NJm{Cd!Q}*I(t*`bIPS zF^|(tQ)*or{<-XD<|F;LcyUelRK{>bf|(DQ8>vCIz2%M1y8Ol;DXwSHEpIyXM)uxt zeBAT-#}ytkp{z+m@i%E1)u(#(`t$}E=N7y*Bj=;p7tvX{Z#HMJPj$~M1*)&Etnp@6 z{JQ#S(B9t5{?{Yhf{HJ;n5MfIFn3N{o}%NV6RY8{?Tov3H@sMpj%BE_9(0Y68^wkpM+J#!SI)fnpRD%%zkm8%03zxO+ri)ZwS zQM){o{?&9;>B!$-m8X(b;da10X)w3M(CGm1AGN6#s!DU)3Dj8Pq2rA z9Wd`>Ul+1W^A3pYvj_>GH&u`~Q5Gw(&@^ld5PZ2sleGW5s|+2@6aNGBQdTQCoqN?? z6oUJz2fR6$#r>3POOsbV%ys7C@~oE>(&#*o9!6DIj$E6(t=P|+RkEr3=tHNl#NmqW z$2MYXx+&Vlk#8<%MZVd;!M!anpRC7N`p#o{f#I6(k+Ini$|Shg3J@;O19o>_}bf8 zyfDYf`d+jtmpAw}{JSWx*qrrE)iw*e;rZjeS|86!+^C(~=PRxJ@k*+VL`R;kZ!@do z2I|Uc_8f&0T0(X%(P`+sAgbR@Rf}7;Cq4VIBDJrZZe5AolxX;G#>N=6RsPP`Rs5`f zdQ0!RQ~zOJJ6dHId}&}>=-Y;RbW-hFXs6jR^gy~^=i|%tbKQex;u&R_uHw|>#Ird8 zLzthl%o}2^e>?uzJ@`%g)+m8u)4%9c`2>sno9dYY-{l`>m-D3DsTA9)c%0j+#;4wE zlI^+sKE|A|W*n!SIf4tH(Z83g*AE57R)*Xw^%?a=)W3o45j*Q|Z2ORwl_%$qdFLwA|rbXXf>CpaaR2`!5hN0v>C8?It3x$4BA*tbX|1yQEBkaC0 zYR?%9l*!*{WK|t`zm8TcBLuO1^vOueS2T z+I?oPk>_~Ib_#}OJIICd@(*z`mP*mny5)@SSv4Fcmelt*Ioprk@nQcMb;mD{cAepC z*~aLGKw-ghLC8;?1D}ehwDk>@X6gM-Fws$V1dCpsz4a+gMCY-r%9)yT4XpVO{iqyX zsh2Q+SwSg16pcZDr;8l9!M!J9sy1o9&u%8Anais97SAlnmrmEf&685rmoBf(MoHe$ z<;ym|o#(bs)#ka%)rg$zlXY_*-m=e^fs9H!M-+|c zJs;GDn>I>zojEdQbg7p6^mf7*dxiN7ZJ)_mw@H03{@|6ydihQ1be8KjcU&=&mBD>h zdve6*MddK_sWzCAHru1Nc?UDQxDFYAB%?D1&RNZ76ZR5=h&Ul|V?lp`;f|vHLzhz_&{GNUITy!gYxuSHR1dG1- z!|7)f1~kpKZgG7!ePnWpk+Y_A-mY>YzrEVVU%x$OAwB%I-un5E>y9PP7E2Y^?~9~n zxh#{#3iW&mlU^ASZ%|Ah@1T)k{8b|_S2(U&JLn3YGAg(}{wqYs>XWvI`|LOWhSU2P z5;HU~(Z3XLwFgm;k8KCDPVQ?gY7b)wiRMh3;&5WTqpo6vtGnATI?$4zWg&Neb&UOC zkMow(54#cb*Bb>1Y30oa9)>E-R%(k^rxquM9?dwuJ=gYFKgl|MAS05gvO4rf;jt5j zH;qeE}O^0-E8 z>DNzsTx2dcr?W zXzdGq*?+6scz@AhHo?1NeAD}>qg4M=8ah2Zrh4XVnIcoBv|VIutd_S-Dfvs*{a>^$ zJKmFb)x2qcj=Hz6{pGeq(zFygNo=EM&j8!Ce)Hr;?NsHOXdC|(DX9>-Cnht7*%60| zq_hgpIOnvCUDzNw|FX@wPe?aHKIA)A?5EOxcCvpchbu?hu6~V7O^S}?JsdI8*hI;A z^0~XwzS(;AqrYB}gKH`po>>Y8k5gs7k#RZvn7V~3%j3k`}j+q)lMKe4=f^0zZbE?{G0TbbJ4%tl|MpvK7Kv_}2( z#i}a>f3IQIUFI*A+0rg?m-Jn`hihf?*s585YVoJ^x9n5DN^VlJ=z8;vQw+Ki%IxpS z%e$UgUmSYLU{L>bkEW+tqsctC7Qgw_Q&yVWjkH%RjVuE>lK3xQTCM9bpExpodg1aZ z$veftULh+X5qC>F)JK&x_6YCimN`}F_?z;(NZGWez3LF9V28QU)1wCag{JNL=w5!v zVmZVY$G`tjT?p!v;^z|08Ooxk;nqotnKg`ixMa0cF9*~(WxW=dYPBd>Y+h(fi*p>X z|77eWcK2%aR+qDDmf2$OMsh=lYxR{IH-Ft1tnwKTV|h2V9b_UIX!w_!?Zx%^YTxma z;z~D-PfORUEpM#sS!3M)$ocud3X0d${#9C(Z?46R88MuF;t{)eIQY1(Si5h(VzF9s zntArTL5hKe4$nc#2Or*$o-)(l!xxrGGm^1PQd@o`Na0y7e>#Jq%B{ETdXcsDS4;PY z(#fRY?ie#y2XV*-+#NV+lfeHWP2oqNzU7@DA!SKA#m(N@H4mBEKR@&?(luVX?W*@t zOM!&#Q@0+y)DO+0Qa>cG+EIEXujIE~Vi6y5Z??57USye&4L)O%PQGxGWZ2QIsOl?Q zk&X1ppCKt6-~N8@I5946BOj4s6W}}gHIU_3jLfD;Eh#hRIQRJY%ITyp=zGSEL;TJw z&z&fZPv$dzKRPG_j^7j!e3w`07|q4(WJSi5|IkdWjK|I)Pn7wJeta!jeV(P`aE>1hzGUFUqu;V6&!tX9W1L9_Qvw0kWFgNoL)uJgqhkz0zX z4MK-{xP90TluD(QsEoPMhFR->h<8)=C`0Y(@!*?K@#LDZWxlFW&$Fm{-F(#2VtKYMCgJ9$mSRd}iMY{!qEn0K2Vy~0nUV`37OD6i19RWYZw z`Y79cb;b`5)rPo;o1chvyV#Ut zUQ_TOVE%XTKhDw7*oTbsBuyfuP11V?G&(6|i(Zn66ulK%kCOeEuUjXyp!_0QF_P=M zi+k*W)c}lp#l_A|#Sp!N6$ivPaSMlTV9u{iK3fYQ7eEWD#dH6DRdLh(;f!6j9h;p% zb9qbgqveO8qxoSd-N|O!^xOi{RHvZ99{IQV&Vom1&YW)aOxCciX|zrLBWl%nka9kH zzS=VR$=y37+2yoY2PU;Mr>v!?^+R$YH6LwfEZYo#FB#Wj6wrvbw&_*G4?8>z3Rq zwr~%*-6vD%)}$A@w#4Fs?RpV*$G?6JcdG4O)&hSh3p={^?Agh%*L@E=yxoQx9p+6( z()av{2&g~l@W%0tJ;paG(7^YJ&%mOH3jf2fhnz+I2D2t@+410B+7YHo^Nc<-&9jdc zwRp$a$Gpzwh`%dz;~OOP{C<{tG4fEDVJBM?IYfsy(!xpMNiFEqm$mqOW!UTC11O=`F`Hf?}?$yX8+oUwY6Bbhu4N_ znSI%eU)@!_eB1mY*?d4kN$i|{DT8bB^}DC$On!|1s2sm4IVDp!m+N*yT0$cuz2jx* z_FBLJ3zH|$-*hDp(X&SAE2-7ZlL&P4qo3&r91Ki9WR6xSZx+^UYy2rTBY*ziGZU^v z#aBZ?hlbAIYWEtH>kxbEwJnSm(6CK(n z{DmAkBTtT^&Zv+~+{`si`$1P|%y*wpc5iIZAwG+X(XUUx|FKc9{B6XLbxkifVs9X6 z$yoKI;X#Uf`X)Nm#_UIB*)8=Be~OB&wR)K-ePh^r{+mkQJF69Gs}&Zj6$aDS8I~(D zM!a{xKj?V1R^1pMKA_AQ##=!~IhitMMk4XnmZLG|bic0EiTIp$i|v=|_W8CxrNauR z{+(MIXgWxJo)dHM*R!jBo14G=_4EJyJ0`RDs!fN-)uJtfCT`U>PSeZ1zReToIJKrs z%UtHUKL(f5xR9?N{pfY|;kvjQcWXtI`s%aTdpMPyzk0yRD1k>(}J14 zYEK&}mnbJOwoNb0d8#bqUDCR1xr#CGuMi3Tx(qWxP0jlzK?9cix?gLQF~)j$k3D~m z7WK#vEbKkrB6Qo3*IWJJKYoACy<;u;vETC(nPSqPKcv=}h{B54Nxxv3kgyf{`?&DD z94}jZyShc=)1g@}hmy^(KjoW#9=H5eeU0SK$yv)s$;J0bbeXQxcwqcOJWDE*_s_*^ zd2m%Ineu-->tYkE($y+?wr%l-dv&)km0a0iA~)lg=V)~;6Y{ekz13rexZnHoSUuzn zKCPW!$9GG+-Ykw^Je0@!&8w3_g`!3dMX%I#N*ZFBO;3LozLu9LdL-d_@o?}7AAHGY(%D;Dd_lZRXcdLN9 z(u5V~^Pb`59S)lSO=-fAY zyBU4joI~L53xP{BVPE*Ssm1lGHCBJd8)}3En^?^hN3pkvQ8kSP@jj5#N5xhb7eCjx z^KB4Iyq?&RyYbAGB$%}HuJTisD%4hF{!J;ekCUi!?UpdbZf$N?k1jA;J)!ZS-}$xJVM&~JJkvnx$Prq-`ssrMb%T^qy<97y8ArD5CaD)_ zIT=jJJAQepJn!Yyk#wNRlm@d(&^f{nCYIAH)UVHnJ`dico{sBc{4t_oQY2( zrcC>B)sw{!ZsfsgWHqWsaH@dw<8v>mXsP5G1I`We9FP9| zVXBVdl=25btL$85@37xYw++p|eqs|3Mx%soTJJBGzgPR5P5Qw%+T$d9k9@3LR%Tq< z3|2Yj;~*nN`?VyEwNORmdznICYGm2{T8+}{*s zIaD*xak$&bLb+rxCu9JeAjkAoMESyF-i}b6F6IXtCyH3dooGkot$)V-TowB2Q~x06 z-S60~60Hg^m2&xK>5&6p0*%}5%vwV6RLuTcJZpV#{Z+uty zd-}I_r@#wAIw1_5P>D!q(>3PovA)bVVZ#Q)q5KZ({67uWXQp-S@@&*?O*&(`Bx=sp zu+i7kzu-+ge74K<*B^?QtBX@g7L9=?n!P5jE4#M8liirwlviE9bKx2D_rpp*yKM_i zTnt&3GL&8QrPE7Ze{1@dxoxz~?vt~jRIL}o6W2bK9`Gf{cQJVLRaSn#bbH3%+NKG) z%E6KW)f*w|r<(V)Xp>$`V@(qORG)hEabk1pX{`G76;pSL;RruB5xKj{o7W9#yB!2C zeT-A9KCfEY|3-L-%&lDt`Qfj#@M_j&Q{?xzN!frC%dH!iz4$_M?Sbcnrak(PX0 zDlew1`fc48%`yFA^8_sU{)ZB$Vo!g+E#q-Z?=<^I)t~QHa6cCnWVCB~e)`k+Ub|3& z`_Y}7t|dv!;`~>wgumluZg;_*35V`i_f^rz6CB9M;cu$}YyP=O+l* zhkmKgzE`?#6w4}KE!BF-;nn+!i{`YBrt}l93f!={eoMuFPg*=>-Sqo7Nu44Wda+;N z$f=~Cy+d*Zm7b*Y{x-`)T+^=>@)l?UL{_VXO4`&vwYon%mw0{Pvw*qjW~9aIi+z3H z`*^5Y4hQ~iy!i9q)X9y#-nTAA+^CDs)6-@$7!~$^O-FaNEcKMAfW69m>j(KOzXo0` zY@htM*>C+XrvGI>?WX*}S;~WxmB+k=R7ZV!=0>-kVl8I1{`N(kv!xA;3Jf-iIQgwd zEjKl@%RG~LIyB$*=2Hu@VEM-v%-zz0n9vE*Hirz&JUr+=vsDg{Oeshn5v=b~3o&Hr zxOD4n*mT*7zEXQ<>TmLx=so#AI0SezFPxQSo==b%lyscdIUwsfWY_fOerUaJbRrF3 z#UawpD`cecF3a3;r!^Q(Nx#pT&whWz=&&lY@4{d6!Lf_e7w7FNw}04C+f?q)dgaJ_ zM*RY(-?gws?)}#&-F!%#KNoABebmTbnIm(rqU(%J>O~UKWJb+TLZxXzwhRu5Q>5?3 z4Mzf&Cta8%Zed?l9(dSVDl@#li1caX1xReOfX+q=|%R$^`3~Fnq;m}%s20V z)PyEJv|RCJQt|P;RvXnx*~Qxy=ELQcKEl;rn;*%G<{mscpVKS&UBr&|Tgvc8mYCaW z@}sHVjrx}_tA(iM9X<&iocfd?*W~?KXCl1se4^2zH$v0T|884S^X2Z7-zbpF7>f5g z{mj~I(s(?5w_dr}+YOW90R_@?1~dpSq_^B{L>54i>N$$egP#%-5tpDRo7* zNbVAKNkehMfbGDKzz=zS;?vmg(OEC!Jz@&wrrmh5d-$Cfrg+-EUOJx{A{K7jkyh)X zAmynn_2*2_fPzs-jk!tbp_K!Vi^ul!8_k3sbJ%0Z*htSQ9GF@)+T|k69T-}0hB9&6 zPKzi1%kgfLUq5esZ`WMaY>LR4Ses>*A-$Fx*YGW?uSC$SWb|ckz02&`q^-82>Fk3&AAWD!(r>H&kXQ1X6j}6ze`!Z=>z;XiLOf@#Src5>Ww(j)NwCSY&vP{q zPEl9olt`!Y)Hm`uahJ68zVq$H*=r4ts419b9B(*O_OJTS9`|~P379GuVtF)}>(kfc zz)Im%Z2fObsUp|<+XO~_yT2fE{_e8md*5+O0pW+?fl~JhqnCVRU(BDFvAPzrLRMlF zpyjK@w*THUs&Z1Y!5vgOtVQl{B#hStlt%Lj4a+ttUegp}Q+J7|w#SPU$wbDwOMoal9ooYm>pcsaSN zi_=AwzO9ts@QoIj_`Kw#O>%IZ*F1rqL&E9q5eiLGU+lDPYOD>@+si|k-b1Mk_m52; zrW-ckJ)Yw7G}|E)kJc;ka+R_qwF!6ECW^@f#x~$4NC7QukC{kqOu6&t)#o z_~LT>RKBWz-CQ2yqgtC1DQC3;sTo)I3o(}qMuOw%IokE>S}izd>IiBtN(OGeB026obk}0Cxx_ibQ__+~1dByB&oN$tn46XjP*tyEB%Fklz*(;j-nZo4F6Ar>x z1h+Jgt~9SI4(9V_zEIK`H;n9))iMZTT08KHf)y?M9_{&N2ptm;9+Mq@HlK!0sI@n) zDT_;Oo>hEJ=sWMo9Vd5FlL>eI5$2MSr6r#Fc;ok~3aX2L_uh1lD`nugeEN~jHHEs- zoYH%8_Noi2EM0fcrwMM7e274;<{i1$+LUm6^`?jBQa#%BMa9!URhr2hU5{$_k6=IB zjm0}BIGT*cjMazQO$3?oj!(!8=k*)yrIWn!emL>okR4B_D49maPlouRyDW8eyR*<~;bmjh95z*a^xs-bu(VYCV1=E-6x+E4%K6HB87SX5uJdezE7DFi zH&f)@M)Rj=zZuJW=fn*ze2-+`S{Rp=C$-ulL4~15$|;s-C|PJmr83o=`JZ0-$GFX^ zK{_>hK&`_6b#m=v>_xATSa*7-bVX{^E$$ZKl39gD&W}p!w1>G@HN2HR=)S*kd$vhL z&1H3Yt?|G&d%4Bew11-nCf%RplKcA&u8Cv3{#L!t8o5~&;UZM?rL0qc@t;G4EE#G! zk?BlUd$mP_m*|Yl*gie2#LF`*Z2F&%aOQUe296ev3=aZvG7AJ{q-oaIY<3n{6CHsXHAMT`ZcE{7MAMGeCDJ6$Vu0kTmGxRYP8?zUikX8*`Zmk zS>buBZL3i$9hy8Extf!u4An}!^esJ?iW6dQK2kWw-JB#SCgV72{B+x`-kP2~A=-{g z`gCpJ4uPT)cuz6x$ttha5*!(-$1r^2&el~$G>a$yw;c=uSOcW+q}(}n9#Ft`&R4&3CR zX7SIb6HBKMxa{R8a|(lDepK_v$+Xp~?{K$g|AL3;^F3Y92S{;wmcoTX?e%PB*u!6+ z^4+f=d+5G=f(fI3@8Po|Ird4mkhkttdm?VAFgldTq)xL)#%Q|r2nYU0QC zipKGF%9N>lmgo1x=2AT@`NbF_6h1))Wfc4bap{mo#Etr{$5oZ%o-)&4j|QeHFXbMw3O)0q#>O+67T=w>$4 zv%OLsWkDC&!!JQ!-lC_+@f&6Th*M7D?f0oE)!Rl6ycr|Lx|W~`H|^SNp}HP0FLO*!q6D`H)yrP)zTKdLSBMYXTE zbnHD)6h9WGd%-+RV~O+7vEIxR)a=Tcv(g5*xO#_j%e-rStiu^X-S6+qq0%pJl!>RN^~3`qtH}@3cT?$E)nc zk6Bw!dmqnC)-lnz%Y#dSHUqC!K;9KJ2f&wZc%ZEuFmbbTXzf?+;Z z6vn;Y)X^XixIRQ3^ZM6uO(WaFT!!g@k_Wo)Lv9%ZG8G8~@9?3av0~2hE>Up9{^=e1DE!9q3(biVe_dJ{bJtF_d%1vKQ z*|adOBgs0-ht3tpT74*Q)uX%g*T>#7XJDeW@#yI{4&o~et*z^NEJ$Rj0HO`31 zT?zN4%@2RYG7x4abvRj#OJXJ)ZqL(YvUV_ z9{9h1_nLSO29cJ6NNdnq;7x+4GZ@*`? z-nJ`bl^l{+7qpEtnT=;Y8RqXS&z^!EK4TrX#r7sVTzz(WBwjV*ICDhYvx4=%ee-2% zpGKHiT4ox2YWBx}R*slHpYb9^Z}i@ulVztrsb6J(awhEaD_LiY1FJa0*b|FKzHl|E z>xvXbNxqKtR9C&wH`~W;FLdr~_yntStWk&Dx_x&i7j4H0pZi)(e;bV^rlzfCgw|QB zI4mB?a>lv&vZWonC}{5xGN_(xbu4z^yPS_=KxnnXx40bL49{|z>-zy-kxV!m0t;Q?KlMxqOwpOdHGlXGW4{u2{ceVp^Op zSbN)W|B*y<>!fi`;9BMhg@zj{M{Ohkkzxz;r zZ**pc(@KHaIY|4S3F))xlaY^}o?sac2=R=Ih&uD)k(`u>K9%(h>1#fm>tXLd!~fTVBX`$aozK^Pe5+P1am66)P* z?D`Q?o}5vu+<;!uLH`etY$_~XM^3#yKFmM-gZxyy-_6URqbDh>K6dTB2u6VCSS8QdG?;B-sybc?**Zw}A5 zrd2QBR8Va6zBQwztr@9hktB86IB-LZ=DTH#6)4Qg!@xAGyH%*oMjf5Y`Z)eH>^cmdZDqR{4K0e$%;Jzfz z;8fGSS%R+hix*V9N2l?US0LU=6=&DPfR2`2d8vJ>C05fIb(0ro-$d%&WT(M=LVeq% zi77@gj%Pr}+^)%6{sU9x{i5q4y%!jJ^Y-n{Wm`P5s<_9olteuDxMNhZ$<5cC&4R4; zOXGJN7%KA*o?JM8J3yv{T3&u{#RGlzahWT>>fH`XJW7*^NUJ3Gg7bjA zm*dv@(E8Z$W`E2?)zBNmm2MG%h)69-K@rV}WtzbuzB9cI*B#TpYPx$0%1f9gbsRAJ zwYmK7W2SjTnO7~pap<|U?cy-|#DUx|n#Tu-}p+fU_fB|Ym`#Vw?ZF<66bU{$E$}p}}diyU%L{GXLlETER)CyUr^8-%ff4XXB#b zv!jV^``-?F24}RQ;Uley3;b^fJ)@xl@VTWsy$4R!{-1kKTSGwI#m3d;s;iTgr`673 z&(Qh5@X4nR9#=ijT(BVdTv%W;0980=tzHXAg+Ux zr=16M#IC2Ek{xt8sfe1L1Gs_&TpcM!IDi(MuPd?R59-cV_TW-g;1wdq=dG{U*?8iQ z`{ocsgNrl4m6~=|&eR7k54S!UF#I4&ryQ)vi{Yc=B`5#)PoRiW@$&^K@v>zZUb*ff zXYu(_!L7CZQB8kr(0rHD6%q=RaSRV&jXTmid< zSUdH<;6TwmY)r5nBlHzq#E&~?)O`u$ffivv_D`^C&A_(REZ0Q~PvvsIse5x4g{UOG!V^ z=;_sDeT}et==efY{_>@)0yUu*2|vp?IrnNv2`wwxT1Nl86gFO=JN2c`<1D(*pFY7@ z*FpW><@O;#kD>eiH%hkZyINxuHOlX`3i1_lv(U)3>Z-abob}Hu%&qI|N?VO+tYI+I z$ho`sJwpXK-@)(~aXfG1?}xugei8PH=fx;Vu9{Fi-;_~9eOC>`d5tO{$2lc+H-3YY z6#OMvWUA=y-VY4w8osrAEJHuvn&u?UtLuo#1LfeapxisI3cZt1?dBTA(3h!3FI1v9 z={lN~BtF;F1I28S;;a!YGPB@LeO1sw9uB3{uYlh)uKa+J+B6@P}_1QTe~iW z31*J-L+%~EDcZL_cMI-xbkzxSGPUSw}ReUb|bT_ zaiBcO$sc|JllJlYUIzLE@^l`fTKYTWZ+U#&L^@ovwq*Bmj4<2oV~SQyHTA%--X!hr z+Lv$aOVNERtA=y&fSQII{rZGl)(f0d-k)|iTqM1YyaC_>*9j`y!nOQhIV^ut9mM7Q>t?XgVuiu~2e!wKGHl-@c%`1x89N7UWgHL5>s zgL)p9Lph&SG~e>8_7aMF=p*+=P<61Um)TaGK054HZ-uf3ntrHqKKz^p`L@r}R7LXj z4o>m-B_;Zc`tis7s?;?)?w)CR8=n8s!u7I(VR!vvXTozftGUjW^%$=Z^46bg!|E)L zU%sGTpb1aOqDNOy%`FB{GAg3_M!%`=CejoyoP!JTK&Y4j}QW^TC} zD>fTAbfLigd5^9bL%h7u#gDf>JeDaPZ(KAA+C#E_h~xbKlu5u52|5}3f4cMl{80iv zHl1kkgn$1(9;FQq(k2c|BsL^T|G)ws9BjcI(%^i35R8F^P;LZ$!`Tb? zhOc=5-|&SJ;I0j5^#^}P!#NfBhJ!fxhSzxT4QC7Bn@}IPPXI4ZsE=^Z1kvpmaLWW; zG##A5nqkJPBF4w7DlRN0hQeUPF?<(ApcB*axEQ!-7pfA-i1LA7V7aaR zfUF~6I22?Td`>?R2I+{!>x;;V!)@U8MldvFBe=MMxIPTjY2YG=9SmFv4eLT=2goYL zpft>Ggb~{zCW(dg!{PfIub&tO3$=?w><|URjTT2^ zA*I1hHuy#$5G#R0L%okfEP+8uQ4}nRm;!+~F>sJSB#GDp1`5x*0*C|lfZ^F)9O^VQxG{#fPDxQ*diQCTnuU* zf5FOsB*n!*Clj*$9T3(N&l!k7NKZWTAOhjy$Qa>U2X{9>lEfC_P-xgp{0%ioaS4#? z0ZIHtH~#@qXh?bZ@(o}S3d}kjxNHG}2=;&wAqs{Zt`N^M;IIKONoX>m@pmo|FyIQ% zNZ^^q4hD4vo>2S;lYq1aw~)Z&0Jk9~CJ8148r=D?gQ39Of-u6+;KLR0V1U6K38=gi z!T<(OoL#vxHOwKG+ZN3CMrs;J(KvBRd$>_xQwQ z2ZQv(Cn-A^G?rlN<3D}{+Q2}4icentBM18$*n}aL!$CeIL0D>_{sU#<^;LqfZXy^| zAGpkjs4NclNpLY4F$O0&;1ac67^E|}G-($G*GJ@6I8hu5vO{8*9pFwh2-`ItIM|=T zB~Lr`f$MA_e~~1%1ESy%Mr;QZZXk@<4l!^o4}=lhA%=rOrMM)q9Vk(F&PWp50WQ>o z^phmE1CDN@r4>19gfa*is4Z-002*X6cppXFF zut;2164DR87z(U%1UYERp%8aNFt`nZyAd!bl%o)LgE2`k699&|8-hVPBko4PpcDs% zxEle3TnmM`8v(;XIwS6e$3OxIVZ?Swq9tIA;BJr{xU>wKHYmKi;cdf-fi(`oi0r@t zH-mL1OdF^yz~HeY&=9y^KuQW_v?u}{!DA?pfk7D2cz{d|?mq%OA;^KN4k07O z28CX*xDaFFaQ`7R25tk86=;kQ8UxKs5DV}aVLafu3YG@QudoC=2$%$vXVPI%7XF$oMbMhJ-^U{JV2fqU_Yhg<=yJ6=FFoyu{(3Z4m4g z!$ETzYGgPArFo!!g2^5jkjzAZ&$z!OIlF zRuBx9Ba8r7?kxAF5u-=MKGuhgsl)TG%UBv4shWe zBu6wJIIsf&V}x)_C<{+lgss3BSZSazfv^<<260)y(TVyBY#%_&BSMb}a&Ra|*fD}Z z^&xBpkBLEZ0fn#?1OtAGLf8s|!DR_{Kyw;w|G>)+!dCF}9Bf-aWeI*oz~ChWA;$y^ z${@jFg|`F2U|k4)gIg!w_hV0#g^Lcri97-1_22GxhK6#@orWS|hXf?$xn2wNdw zu{O;^Cr za75vA=kMTlMS{B#Flb1?*bsLs*o1{Jg1h16u+XXmVgp_dY6I-!KqMOMQ0&H_sgAfC zEC+G{xIV%#!TNz+9MIK3(Ven5unPl~McfT92NGEbBZM(L26!=q5$wQYVE+li2zC%K z*fzx75DZ!_5O*VBaCk!8jevpv19Aj+!($Q<(F7?0vCcS%K!T-o7Y1dEVCf^mKvCdE zVAp^c1EC$li0uIPT0{0C?gqCDGJmKI#NF_igallcXgqKd@a7&E72-A|(NJF@?uIXm zgEB}k9f{>|P$mp^Fn3|_a)GcFLRokjMc4|A0ZtArD+pU5VDR`NYz2==Kp7QSduc6&S;a z!a5^tg@8dDSzt*dY8L~TKZFt6fe{mh#sgt1__847gD~Rpz`)tN7{XQva`<+M#{(k< zr!WXxA;@7MT@bcHz;KW*2wOogNEd{y;4!coLD()kP|!mIFcFDugEzN;6Yj>~`gYj? zvj(s^xl0b(JOW$p#282(A&l6sFz_ar7{XTY`hh(nAcwFO1cU5F*b0n+Jvzt_5Vk_V zU>`!*3WC9MupPwV6ZYo+4xfY~Agh4GC&(C}J*u7TbLa11^&>V93uY=Gz=+KQ7;r7o zUG4_9!63O^?uG?-PeT~-^vA+k4A@vE>Ow3InqH#2+zktDGysfvn6Nk;=t9w5?uNra ztH0iQEmspwJ;oJf+zrOyHg@cQFlhT-l*rv+3~HCi-5?B_ zHljrC24k??&Um1}qcJGFixRmTj6vf@>sjV1SJ(qP_y@JERN3R`7BdXxS4**a`uIbwSt)g282p#{)bW zgmgjJ3SJHiu@w;Wh}(rTaIibM8-w-RWd{zgAF*G7Cv=d02wTCo0dH1_B5Vc0pmq_q z0%IU^h0E^D4=`6np^z_%uoZ$F#A-wlwnD(5%wH5?D|k!{N-snawt`@AyTo>&0Re*K zi0uFvC@Y4r6?|E+j|X8p%RJBz?AbvWv0niUF1yPP@URV%BOVVlKCMC63cd{hLUP38 zfkxxoARZ4i8e$D#;E2WuU~s#;>;QMv13BcO9=;8Dj~;+f*3qr0JO_CkRt$SmuZq<6~H097_YG;7;zl33qydw zfa7-g85#qW#O-o300AX-dl?4I0vtk#;kqQTfa>CQ`4~nL#9Q1h7XuI)K*ZVu$_+up z+5<=uK*Zw$AgFrcVZmUb?QsxEiFyZvh4w!|^xB0%`!OI`@5Z1ojgVp30`S@ZEJr*5 z0E6X-M*#nNf#@#x!r&lM4}v;z8#stSi4waPw0jRtCxi?`?E(xAdBpAoVUQd`h7mbv z+9B)&kKva{gq;vDID8=N1i_%`NyJV-yC`VS45X$zIs**K%teXV2_y$i6H$Z=ciP#Aw2ag94JApB1e2Lfzz`#=qfDy412!k?Yu-Q!1R{(?Mi2Mr3!AlSk zJAul=VU>uTz!=o02pNX^6nZ}a!gkpKI3$D-`4z+?;C6|o2f*MlCt@d{4KzOWBAOon zgEmjV8bNFa8e&u+3ga?a!|G|if1Rg z!X?z|e}_vXL_&L=(9bvwG;Mam<<8%6h_~S(urt92Ubi4_7(DC+&@S7c4M*^*1+f(L ziUoN8VHX4iLd4PV)q^L;0NQ02H;eu4)HET3aXyqTnGeJzgv6oj0$YA?Wzl8 zb2x*2cX@34=q)@y$U?b1ki5nf#c$K`xJN^3_!cI2k(#o zXqWbA5ShViO2pbrfIt9(Gckk#&w>DD*n#kyH-Pl-K#~~nY7>wm(jIgRT#(3fK(~Os zejLI)pq>B_2p?ekVW%ztfvAc@cn4kz4K0qyBVarv33gs^2J%Lr4b!0we*4 za1J~Ky>Ep>COx5j2=ZXzAcDXf z8;}%{=YWdA8xc6c8S2UI4qxr$8ATA9$ii+#w*r01(lP z00lvA0bboBmI5zd@?m%R6nMK610bRq0lF0oI(C;&fgB74AmUNMLYtJ>T|NbVgCOEj z0X+s(CGsgiFQHeHutYuuASgEkDcyfm1&=wivsu+_p2QYYU97`0C_uj$z->FAS1^TIL3d< zLVZOb89NwggTOL&Fwh2pX6#^~4Fb>D!Jsz&%Z~r2y|deq>qzeWy#T!fp@m@)Sax@P zo+?73A(11`V96P-B(G;Zo{J_~k{TkLba&Iz%&YCiKGMFz{vz{yWW+yCR}J9H5nvB1 zI{zm>A~G@}GBOjLxa&QQu^fp(yWZ89XjVt)hsjv)Y)s|Qc)hbR(%5?2_s+&dL+AC* z#zaH0_s+&dL&f#J>_oFVd_OEZg0wC-rX<2b^ZdZehvxgix&zJggEZEMj^5drXjVt)hbimc*%-@VDdGzIdYN?ZZOVMQLz$F>AHCBAYtA-W)NYg8PnB$Qi23mqicwF?5b#zpOdz^#cml11ph z$C};+fg@z`a2Et_ZHgiYoEbQ~AaIsGvkL-e8IHRkaBBvJh_P=A5kgW?1I_9Pj50+L z1&$4`T@*Oe;ZfjBQAB|=MG*zg6h#y`T!~#2INZlw6gbR7(r0}?*qkAK*3(Q;M1eC! z(R;U}yx79g`x_IDI(mm=qESchaf~z+#jbZbCK`40KF36}Is!j%d3U|nF_p7Ad_Oo} z3C+vZ21UX7HrL+`ielG$9>e#{-eT`Ll%tN`_ZZ8eD2R^xa%_^2O&VxchwleFchEdP zEQe*+J0N2nC<;P5{(C42Hdq6VI(i>u!cs@?giJK*=)I7U#ylt6)ql@SncfeX%2^$u zAI$Sz?}<$1td77B<~eCoz7FO&DSv@R9lbX)e$VE4?~Y6~>gfHEk!JI}cSt50b@ZDd z6V2)<{csA@C^HIlgBtk!ccj^v14H6b6R(`UipGl)hmABy$k7badEha_RyDSsU>hLpXi>By$r)4aMrobonb)YG_ z-ffx6QAh8$Of>4~9hZql9lhr=(##_0U6+Ywb$Cs-W&f?~otLSc)e-t(7Qx`Y^ydH8 zEP}y%Aq|}wXNLs<58g{9VhS7A2j`^{EsuHyu~%jT5%UXTua(L5v~PmmL+qK-6FJ*t z#J)Ep(WcYjxr{_&9o^u%OhjvEKjB9r?o>B8FB6f*58g{9Vszr!c7yxUYa6!LI*5Ib zCL$v@I4~oTND;A{DgqM`{tPb6L^OCm@h2jEADoz;$avEC!Hb!QR5Z9TBe9rmW!ZFU z)dn-F)d{nD`1y4j=f}+0FZpoV&kmEY=pg9RzeF z!WD8E-4LwEorKskm3%W(;v0_rK#B?BXw)Ek45YvIktr!sd9!*4=G>GX)WR>Rpq;C>Ch!8`M>_p{u5Yr0Z zvOQZ=WC7jwV)~rU^}_ia9lPyi@;PCsZSPV)ht0iX^PIl){>*cl z(7Q3uskrxEp3{ZiX?ae=dtc=_tm<8q=d`EyOkNN~*`JY$xL!|U`_=W`;rjaW_6+Cv z?8R^Y`mpPLmRkCor%%s*|Nidk_2HJk)KMM(^3{hAH}C)R@aAm%$Z~!5&*d9ccxuT% z{N}~k^UGICSzJ^aVVtDD0+uC1^y*3qx!{^k1Wj*oqJ$AuNQXVlE!DH_2KG255r&U z9P0nNKI3+ccbC_1hQHRyRQ@_N1eOtsEaKzoD9_$G@^qTmJ4lXh%V6&$dAfbSAAk*A zVqg61yTi4qo3l$=|L*x6qzOD@k~&fC9OQErC0{*eKFf8Ap!Tcx%yYa`Kq zi=Ve#EOKis@13nua#IK8>h|{P{k47h<;UBfUVXf~&Yu6~8PI+} ztw9`XFD=cml$;$#2uGxu;}crPQxNLMNn*oq+?XjPyZcAV!PWBd2#l~uMdZ_fBXI6?rgakgdD;A;c#=f zetkIm{_@q^(!_p#*cXta&Dg|#L8gv=UhFBcJ^SkA@6P`4;c#<#hYa(_ej=1VUM$L= zzp-&X`|iWx_0Hj-cK6f4fRyPazLr@}Uo(6!l^OfSNVh&VLpah|`34o?%Cijiy5S|~)t|Cf_9}s&i}JH}m!He>vv!A{ ztMaqtcb572l)mtmP6uf;rD0sk6mk&|gdqi!F zWmoEE9Fxrj6|lWs=Elpj&7%Aq#$>a6y5p}y^_x}sIdE#TEP@^cuJ zO;>&ngRvV78OLOMVSgOQWVgnCOGdyj;lrH#EW!cS{s?}WT$ z;k7UI?gu|h8+*rtpQVkx%fZjm#@^ZBXK7>aX7IDLv3D@|S=!h;8T>45?EMUW?w;az zYvXjXa{tv%YqehO?z+F)3;= zWn_+FtWbj~qjL;nL)>7BpdZ5+8zxMRksZTWV;W51Z9n2~+3hF^m&~ z{u-$xn4*}*dTNOA7{rS~4L}^jcrmDR{20cIL7nTzFkTGmls|^?Vo+!PF^m_3I{lAf zyckp^a17(cphhK*VVoHBH$)x5l$BrfEa@1=$pJa1r;LG<1N^pAFisBEb!+BW+q@i98}$gLOw36R>Q>A# zjFSU4hW?=w`-1Jyd2bRnqwF*2X%Yq7{<#%HTRBTyc|@k?-<6* zK{fu4VZ0pF!1fVLv3ExPa0ucAo)(*^!JM)*7RA|MPLZ8rU5%Lju-~!%csZy>hV#$qdTc5O+6l-t7oV1pdg`mNlG}cZI`nxIaAA=g}8tdtA7b_Sf#A54aVK#PU z4SJ1${tl4>K+lm7qyV=fv;bf2xyzc>68byZ6pZC>lR^c!VwaH<8^Dt0I<6b1>kty8cP7|wpIZ+ zUI&0J<^q^y^_*~&DBd_uEhlD#qlEWHKx-k*@Vbak1F$Am(`^pm*7*Kznj(JI-O^|2 zc-cr8E9vi*Ifiiz@9&N|hH*Ua?~FNyacuAJiaCaHoF~zH9JG7Jz%jqSd*xU?ZmM%B z*D3Y5+1}rSa-^OTW*zy%-IFKOQ-ZN0hU2j|_D78VZAoexLH%VZ#~SAZfjdo4smBRI ze;3}ddb}W<64R(*8ALD6B z`f4yHe@8KHsW**s6yc@d6f<;NQp%>5)l7;bQc(Py33Ez#Vp~$u8q6s(p#=9E%qdb( z{HY1UvUI|@d38_|AC8QHj|jGg*t~=mA8c$Jck!Ljwi1DFFsF=LnPMa66kSjh(}?J= z6+SisP8V=0@|51VMWHp2?-@0>C~%$HDfKvA&|kNEtUpc)`fGNNV0=8Vzh3tk#u*3w zwYtYJP8YOR{QS5TWj67&=8hh#$FB*EHZX&bn21%^IxuB>WvryXY_e1WfQ)SgI0-lf z;Mrf3bV>~~##he;dN-^HWwq#H`sx;&zu4R+)_Uo{ggMC;@?pHwRzV-e>n~d`Gi!cD^I^RH(UD^qCj}>kW@}RFI0hUd z9_7GR5K>#hDp+$>CqT_79@KBeQrGOxmsW9bF$$m$(@8(bMHPfo;Vr_LfgvFP zr@~u+HENyc@N%dz?>N5Lnsahehhw;_!w`gR1mWhkAaujW)M#T@34(beb-39r2()%Y zl!Vi~=ZuwEn1XPAc&x)*C_%VYTM)QZf|zAFXPh3`lPiL_m*-|D3BqY}*DC9|?g`f8 zq4`)@s}gPNBXO<{L$Cr#tLAxbts;$I5c50-!3!6H@G&^oDnno+#X5WhP7u0nSC6#j zV`X&^IFmZ&d2R>|qSWKC^L4P*Aa&f!bGwXQ5cBigT7}gqi1~RAg2Q}@xR>YlPXfbA8T{1vO1FW#s}LR!sD_+~kL z0+?kqgS26;2*AzgFi4!cRe)QoBS3xPdcRiM2WyhL#P#y6S%7-P^=7VFfI7tW+O8D9 zuyUc3blPXc#ZK!4trvdH)v(qXT5khO0gTd`#U?V&htk?6(VR8bjsWiC^qTu?1aKdx zxyDTaPItFWvOW-nkQ&@79RY;F1mJXc1hD570X~!#0QT&+0G#e_0Sv1>j4lATO1A(y zZ7;zKz?t9?fY%^^`{uO05i5ZEIK3j+C4l=lZLbUqV3yN1N`#~YFvn>WpS`sxm_!xfMgBz0kk09i)0P;d2JDptf4-976IyG)r<4eKG-N}NUz?imjY~* zG@@6p+?xYvJg;8IHAHtx|_tWc8xIv<|aQ)Kjdt0H%Oq zo+PTQoamlMB)aVWz?o%i##wZK;EcPE72#C48!9BkE{BjhoDLU6Vwm}~wTQ?pvvSMa z>{w-{S-FF5MDQlU=oY}hWJjdlsoelfWU3zlATtS=zl~5?W=sRHbW<59r^naLu`@Vl z4`N4vkD9HUvtTBK;053o>=t0VI_xS5z;QbOxaLX$j@fNyG&R_zR#Jo0V^H}pSA(0}EvF5@^)b>Uw_vx7n`_d2oVIrvrG~(18|A4Fgq~vIc1m}n_GZsKHVm&*STjkljT)O#5IpB)%B}(5wxyhQv4X`DiVGPIHH(jM8kFjH=gqqN`r9pLW42(EZ7J z|NbmMw`JV#l^oo&+vggBOEgNXkN_Qsf zYXNBu2GEVk`jkKluqLT*R^J&&0ak$4HF z09`}tn-a4CT|?`8VN{sCz>G1w&{o>y&2FDEZ?~NZz-jOH5OS$Pw?^w5YH6bwSUb}vRXBr8s^C0^AiUun zdXcCy)M2wwOBK4b*Vo(TdXemP*07aE(YPtv7;GEg{YGEn!idqYNU1o(Ja+wD??W=q%S?$Sol zi)8bnK8BY9tP0+L(?&Tx-ZsjrP+P9Pq&HuM`j_>gy%b?psP$K$;Y$If7l|hKxn{8! z8d_B*oMR4<|sq z?|4W8u$xe2nEb@{fK9@=5GwNk6WLfp$ D(lRk^e12IQy<=EciFxJ^at2{q5UZCa zIoGjV1F(fDe_mmyyw=MPdN@U|D+;8LhKt5u^q`sheRnfW{N*la-S!H2`Cr zZhO`TEmHtBB=NQS++_nWV{IIz1=pcUA3Ud<>&j@-I$7U+R#_Vf24J@=N)4XVMNN%O z%2c1vDr-Z>)L>UB#~OUNEC8}j`*2wsYqlDaIqkz`0l>Qz+9apG+u-zEAKaYg>FAMh z_9*>^;F$E<8R9L1S7$NZlW}sqZV^^Tig439B5duJRyl6B2y0b}a1*;lSgTenwXqI{ zuvtu7gw>HE+EyC(Z5su{!!ER=X2t2oL)tOgeTG?k47_kK zncqIetVI+l$q<3(lV&chN_+&LWEShNqlv=7!1Jk&H6Ke5iwhP`$MgnbOxHatAc5-> z#Cl?Bz@c40oJx;f$svL7Q!Un)91<9BqcJf)nTRwj%=QUV_^7iTh_z%~3s%kTd)BbL zmcaX|78|jR-eN{AVZu)kYgi7kGHJtD)sko{uQmtfPnB4^>=HZSWU)@uN~~QuBrt!f zWsUQlLp<|~);PjRpM$n)AhVn-k0DHbX(2Q$#Y;31YRZbwi6<0`n(`)sjMd7_Mc$bw7vP%YB}QSH2WKY<7@y zNZ`JWM&r~ZmIdyhHY$U!1@V+$!t!Dh@=n3wP7X@%gjP5 z9^%xh5?ZJ|-!QiJq@Y&f8Q(yPtf=+PwK87iHxP3nlB3Z;JmVXP)xtx7+AtrLTjAml zTr^0!u9nj~Y4=NCG>eFadCrH1ne5Am`82jwgk<)P56%fhGx%tjpY~1n%?{JFZ4fp> zP4A}xTeD}9oC5+9nC~G=y)>B{QUdcQh>fuwu9E@tQM#6swriF{yv}cWZ%3?hh@bT( zV06UVBbd;RSOc+!r6N|iJq>aTp>YHJn1Jg=1+>ozT}X=eP2s*5d)P6?oSZwOAfi0`^(Hm@~LpK zFF7P|-zq&KVh4^06{lfheVxLVLW_?Mn)u1n7?oSP~T5`y}+~;j$=?k%>xrSLS zImFNXqCM`HF=~XC8p9Gq_8rHaN1>Z_tavS zU`2sJ_0K^HD^rN)e(1{*A60Ad+;1SImJAYOd?pOj++S$M=6srXX$*1@D*QXtRqQSpdX&~zK$#$z6kL>f2n}IDy*&YjBgNF`}QuS zB0S%Vhf(`sp_fb^{nHEXaS>cry#k9PJ$}wNtwOWeUbwU>g!VjQ!)Cf7JkJ{h{a7c9 zyae^WVF>hA9GeiZAu<-;6VaQQy8aC6DopmoQCoy~UV~Vp&$dYj z(DHQKjs!@u%e`3mrxn_EZCL$sh-Z7KB{{7|En&h>T(rKdG`$3fXS^5SEHG_}Tdw!E zMpjWVn;;9FEkZ=Esbo#2Tn-5nKGdQKc6237_z6;KNg;lL4-MO3hl&)3m|lcv3N6c` zpYj1>H#lo8f%#KkYz8xR6cKpeAZ+VHb6{xKEblGTGl$GFe`U4k0cmRS)4uJ!)sjMH znQyh&ML*j8S>_iAlBp2S{F3q3>pW^nP3RcYGcNUO3Vq2Tp827cP2#34eD0lP$hWoR z5YPPvVv}-%&`9?~Os|31h~*H^{RUFpfy|0Tf4179ffRvBA)fmUq=;n-@!W49rD1xw z3d{3e?q>mqMTqG&wUmZswb0mmy1&#s^2H*=^g=B;Byiu@G_Bs6hDarT>Ni%%tP(Gm z7f%j%1F_AFREhgTtnoH1tP~N-;`xu2vuv;*encnlMc`by$*gI&_ ztm65l&9X{zh~s>`$vFv5*&Q5>ti)#FS8KBz-&;g!Rtj;9Z<|HmlT*K(m2#85MOY;{ z#7%mE=t&l8ag#oFCFQ&i=Cu&Ik}}>OY;D_RJBxZaYO(O4ynt9GdpHXp$!if7vsvjG zFDmhjF9Fv&eW`wnG8V@BOW@kK3_xtsIy~P?C~T}F^|aXxX~eO82g>T;ui7fd_JBz4 zl%VI1>n(y6Ynkl!ElR`3nb;y|)glS3*NZh9gbl=`925WF4j;OnPYCNd!WDbI3^{rw zI@OG>D!TeK#?-3jT`GE>MJ1LYeAggoRVF3N5WNeCWF4*dcc!hPj&%}Ova5;OvGR2! zm;Mkc@jNdhSTpcu938iDfv)R<#JzaM}Fu*>~~A=FH0Q!McFR_6(LjRu>V; zCh5}0>H=b^7fURbK2#SGN&4BcFkl)hzYb=hDoc=U$NoAalp6B&E$N8q`AV6-yUdV2?>>(}$94tkzt+%0`{uDvSWW-YyxR>7lI z68(YCZ8mF5IA-FYMA?5d7d{br>!5^SovhTP>1cqX&p|tx9@7( z9K=ypgy*?$mHF?A@H{V>0VB`1d_WPN=MBPURN@KSfwY!`4Z`}7S!6yW7d2dFxBG}( z&nZU!gW0AcC;Euk;TN$2=O>S3pYs?+tMGFZFPh7T`xf5XtmewzK%7@ zUiwjvyG|Sl857B7@Y3hj#aXCFcxjch;=-E;sjcrb>so|q#cY)dvAD8mO_G((^bm^k z2s`AUW95175%$`MAmCFgB_6TK`Vm5L&1IZ?D~+*)NSsHcYp0LI)g@>et0cZ}_kXqh zD9gi$$inDLABn3A%81B9qju!M)nPwJL~_jlnGasOH!(<)lH{aWb$%ylZxA-4GCvjl z-L@(q65G=5nP?G31jc@3Hb4ysPOU0~Jt8um+aq6X9gSSsnv+=7D<6rAuYwTkh_YKB z92{HKKCELZV4Z|5S7jxeh1l5ut;KP@t;IN!DC?Dv#kB})*D5hcS3VfmLKv&oB{z(bBIDQ|5Sgj5^1(Rc+92?>DrLJ5#@QB5gUA+yl@G?X2>M~K-3vo}Fs{b= zM`6s&fR#_7i-^SKUin~Li=gMLL@nC&Fpa>s2=+wH$<%&0LoOniK#Fivy+s(SEcz`F zAB~F;yEa=P&U|lQ#G)r#z1eiJ^5M7^VeQHx&X#K-R!L%8TY{Av;7PPVY!DXhh+EY| z9oeDX8a$rVLs_`0Xc^lRD{JNBacv!j$W)Mz$F&F(ctZW!kHGe+=Qh=|I*PH^^ur_A zU649_JTAVQmUycxACC)& zG9BzAb1kCuB!%3|`&E+PWY5Fi)0O0s--X?Va~~vQq>s+UzAPDXVPvuWCS}xc#k!wd z^+v=O`2#kh>nLp{`0?B5+57Mw)H}S;Zq7HTWh;(6vjo+rE25@{A&*6*xcH!p0NZ^%TJ`IptHc+RMkRYyl)FH}x%# zbyy|u0r`NPoeDVx$=63rKo-1z$xU46C ze)8ng!}S}J{YAa)Y?=n6l+k|nBa-rt@zeK9Vq6mYS^4N)0HBz(MULSCkVIuxK6d8; zS&(eyLw6H^J`+6A2F&X1~df)swsoOee)h6-G);@2p zMbN6u8#iS#->P-8)3x?_b8Q{8%5Juca$*PV=j*UYo+3Qci}oCijcsyci(L}b*5MKB zLTt8%b|3}>ELo(LM6B!NhNNk7on-b3qQIfI$~aP)AKggK^2)IU57wj zV<^tWl0<-dbVm>%B4ft&vA5D znY4#MT{BjU?lw95VzaERqe0M*?D8wSYj8yT{^PsbKOq|ZmDjDER!P0Yes}(?G2zy2 z9Pa7+kJootG3Wo|>doz+_)?Km`(&9E_79t0-`YRQT4nzzBf&pPfXe<zdNYN^Q#GVrUB1Px(ao|9#y>tFe67zZ9KECB^sU zf9vp-4XJ{xV)19Hy*bcJT3$Xm*Oo>KLtCn}lq+7#hpUHKV)XXA_knn6uMS$D{(v7@ z$F5IRAV<24%E=9C6q|2QpS{9PL>=au%0)x!&K&>SS6l)K(CZFrxreAUm>_%k-;%Zg zcTOCkW)6i0RmYacip{>E!n$!;9xpDxnE>^FD^q)4j$868N9*q2xBM;*Ke<8Hjb6xo zgDmuJ7516%MJLqXJ-y5${@x3G?>IQ$OC}%eXHEay0j5Y5@DNHVLzMJbvB{5`v%p(4e!$z7M?spHbq>6dhOhs zXne1VjGd?~9H<;R`TLE|eSWz9@$M&tZnZ!E?&GUFQ__EY@w{rt7l*scHXi~Xa;?(ur_ zn7Q2l_t}$A_}3RVZ+>|E?Xz$C>iG5LXFuKDeRzC+{>v}Foc*#odw=sI@csV$VtKw? zKBB~<+rM1jUHizWt`|jnd_aE=R{OmKUX#B75*Sim6 zMc21yrH^N?-@iNm_432{;_Tu)1AS;(=Ro`c&?*JJc|BJ2;p5HQ(w{f4&kt`8?^x+> z!7Wl8-(>Lnv52+(I$Is=d+{R24PATp?tC0KhUE(&kDnqncZX;E-xGMYd33RYVc##d zkC)x!&HmrMI1h!UA)VmwZ@z#3{_T@*ZZ6*)UR?fsxWTVJyEt1n;J!#ezj*)V>W9B1 zm9G|$X~@Oq@x?{`NK-O?qn`mMeWfkie1{=_{PO1gn~$##H&4ELee?d+<=um4SGRXp zZ{J#Pkc$VO|LYa;wO?)@esS)KhtE8H|KTq;S3mxASBA5eooG$rH?JT6@c!oA<=vCZ z4KK;p;zq`77dnmJK6zVdKzIuD-sm5HJ2XC)zdOd!7dHv&;pZ)si z&Ebd3k8kfjd-BJx4~IuDzx~4ldkOQ|)sI&%4!1u&`1YFz4D-jghX?<1ORxX=&{*A)My z(iE-s3!7PwCuW$u7Y4P&X2i>kdi?DD>yI{JfA{RkM@HoFt8V$j^5Ssu=(1bAdc*?w z!=wG1?W;%o?cvR<^$(YuA1?MqW?#H$vGU#DUEkhaUcWvJ-@Uwiy;;86Tt4c$9~O_+ zul7GY+Fh>SJbJy^9lFKkYtr^!4c~3B{deo&GHkwr#!UbB!A}48hY!!c zH-q`})2-cyQ{3~{o5K&Eeqw>!b;tjX|8W4%j)~jf?7uCUQ+WFJ--GLs*4cJapzSQU z6li;k5_lRL6++|rPvSbRT*qb-F@iuVZ*m0M#)89vwpAL%V74#E=?9`Hfws4VG*8>& z@(XQYSw*4T(xShCwzBMoKwDcVGSKYFbmU88I zY$#VUxdLsi{q5`(Nh>zVM%UTH-;vg7f4iObcURu`^55HWbyWP`u3U2v%9SW;pjl35 zXv@xy+(nvgVMkhL8Bq4$DEHlNXGh=yZEu+wp0>ZRWPv~{0s26*>&s%fvOgBeZIr+J zt%W2*xz1w0fwr^gaiEpwdmW9TmoeB~*mIU1yW{Pq*ybHi`owYBU92tq9_rZ0+}~a7 zY{x2;+l!o1O7zQ)d`qc=w7NJhyHzK1aK{UEQZKm_(hqjdWenIQjr>KEh`!pbOW4@= zjSEy2yS4CfDA(EEQ=siE>KkZ#nS*FznS;Acxg*PCH%sj=w^B)e$-a;_Z|vB0Xv?M( zncSgc<9yq3D^;9tyKQ-h#kX&}u!P4zE5~C4tt4y(n!RZrv33#8ayKbxVt?MjlEqrfh(Roi}qD$X)c9~!- zm&o|89GMB~^*Z6|j4igME2c!#$>}vEI&7x5M{#qGORX+hFtMIMAoGaxq&dSGF$$%`V@L z-`m(0S16};)1JpSwA{{iqXKqs`@EipDp8u{TgP%s(Zzc<_O;wb?9TmqD|2a8Mr0p*(VZviE zcjbEsscarIAJ((;lCV z>m{^up;;(bQiuc1(j<-4ey_6}yFlAVeZX@dB?-Wn+b%7;#nHHtHqIFg^v*IJTse@I z-4JMECvxSSovIGyu$y8(xFX4Rvi}7)VJ<-HqP+oa7j-8++bfM%B?8|ztTJ)F zK`Sqfos(Ek`<8;nv?Dm4 zCo%-BBwo7qEqPfX@B^cG8*M#kgmy#wu>PVQwqf~*@d#)oH_g>cq#*jv1O+zHR)*Ha zbs8EDQfLb-mws>nBihOYa!bmiYYQfDw52GwiE|JdMqH?Ov$6}}>~o{NLF^cVQfOV& zr<)DSd6X+uyJblG?_t}9wUJ9dSkYrS0x)UAr?s>Z7<`D8jA587Rz!~ zq{9+j6M5Og^Eg&}LQAo~M9AXY$I}oVu~4w8_%=hMg@MNXWN~fWvie3_g`sDcC1Oc> zjCHX5MqRQcAvnf(j23+%Xyqd3cC4UD%mZ3EE#S&=@nl?AQQ{0%Xfq~Uv^#OS#ovOq zjq3t5;Rma)oy4}LjIsf(i++Wz(v}hG%MoG}Y^P(2ILCE$OGG-_z|gw5&Oj48Y`fu( z`5@!aBn}4+BQvy_w|=C}s1lI_u78jA5EFk9Z3bv1?c0ru&GRs)d0(m%`NRE<^N4bI z*`dvZ3FErY*Dyn*oakLvfUWeS<54uJ15-5e681`e;ZXE-w`}7`e>*-G=T^6ueLn(` z7@46T7OPj9&R=*3~Xv=6vKr4r<9nbfiAB|&* zwu);W8mwIK@3E+R!7?ymz1;4Jv&Jz+jf*_9oQpi~39p6zB9OAqK$CT*yI|`{uv}gf z#$v||9R+{hAWB7aPBIPCe`@p3@qFEl&4YM&eR8cyEc4k~!s zwmeH3XywXyPh+_hEWti$3)45OQ615jI6t5*W2_#U_}#csvM-JsRi3tY?ZcFhu_}TG z<)uSkju2Gr2kQ)@WW}bjV&_TZg}6nuEjmp8Xj?$r#kIRzb6aqbacJA<3qjjOJC*?Q zKE@(D&Le1BaO%SRpd8aC^bLb8&JQ9`JCWUPZ&#W7alvelb}^2X?76by?PA;lgS9*$ z>c$y+E!rwGW1|=CNoZZPC!y`M4n|+b#d4CiuzeJGxx2t;3VnlZC<;Ky2U;lF#XH=~$a8|lqOYLIUO6<0C+-%+s$xIbt(9@+)_}NnW3k$~YA55+ zkaD3Bk%%clFVK{in19hO*|F+JIfW*30h-JOOonZ=v!OB5 zL*KBtWDHi@eY7`74Y-K*8np5hq?1W(^r#alC%zxFZS*+_a*1uRBds9X2hhqj*{)tj zG|qEIc`LHPN*mWu%8C7qh9%J>j1|Efkw13Yqz*197x~+8gg?sF24^GammS@RIt=ez zd~s+5GGqJTTjVd@5V>MhqJ2eL0mf+f9xJ?JiOIw{!!i@&@+4qL+}oo3F_yt%w25{E zv@XVOb{3xuwldm4>{w`GubI{mp0hI>*K^8=FGTW7x!S_X8Z^;swr<7tLDO=qjZ%(% zt0-%jG@`TjTtN|e1TESJY$EC$+~d(t^pQm4&|ugBB9X{FGJRpSO>In zkzqTgMvJ-$S~;~I%8C7l^&P7-!NW5cBvw9NRedtQB#tTEsHOX|UiVS7UGSm)K@Jk{AoZ3n&kF zx;8Ua{LZL}Cqgl3tx)|6?SEu0v~k2JUF!-7RA3Kr8{X>qQC zWf_oiI3Pm9L5egKZ=4HU6&U?}wmQTwGg^$5LX$YP(c+p6O>!lT7JW%*61y>4^hu!E z?X6+#HOGN+5??b~+>3@LIVVPo>mW27WvN$U`jlg5NXp52MAn1k3m8p#u6b#cE6+4~ z`NLxsp3^lMD;7BE2YWFhSLPAMesq$@LtF6bq@3MX5_p7trFBUBitkDOE;PxfF`DQ# z+l16Hz|o6s!F-m!;g!hz#c`B2v!$do7Bi_s_LLBea>u#n+pb)t8ECTi1XlKYpe6jk zxX}J?W1b*b*@uNDd%Z@B>ohci@X}vQMWNv-D^2AJ$6NRYROAYCQtDvElsatHi}ezA z)H=$2<$mmuEUlwlD-p^O9g#XV(dH*SxzY859B>&w_UT0a_MNUDd-0j5L(W4OE&7en zWUt(4F}H&7DF$We8&}CipObQU#Zpe<2b3#!%DC~fttYKR&M$y1cZ~(CP5H}Rz1k05D{T8x`oXKb!VhB2Q4iU1gE-IE1f>&NQcm_*EZUirlf7-qm0M-} zT)y|WVJp6MYxCx9h9$CZ@6u~#mA!%@+G$e97!f}t&KVH;9tlFJEJa^IlI zIW(im8fxyZ_G2ISe=XfR#xjg1Yd6=t#aIyK>@xN+&P+IwD~43~ff`C^NjbE!)SqNQ^@%xp8sn$*Lv1N`l#+51&ju@d^hOh3ob27?dnBvHzL6iB(2{a;mV)gH*=L6) zdAUYQz9(^I%CT`J?US54%E^8sG<#+)$cAMf2`%BrCgBHZT8d5hK{}0=BfKf~5=~QD zjK`9tCHcxmOUg-piDh^tqeT`@`!kh(egbxlL<{? z+(wHzv(Pw55XX-cDw+G1sUYR#Y$V@fM^DNjMoJSOo2e@C7icjj0pppAZ{zn+yV4I# zN9hMSkkSv1-HEJqC}XLkT&?MO#15;hDWp)zI!LO$wi)4&I^=8`{k3~w!yLpv*EW;b zC*>q>iSJ3w+-NbMm5nTtAmjI#meOYYa~Ws+b7`~ftjYK60s7E4+u>50u6gYE$l8s6 zE@O{>uKkeQM*1r`Sw_>fEb-6D@=)EB_~&GN>YQdbLHi-+=*eo~WK0|v)SvK!^V7l) zqUOR6qSwL?L_@}&D6+^nW}>tiFIL9htP5$goZqK!a^}%!I#==8wauhGNgV{(l%{hP z*H8PgQ#+PKBkc!4fKUg^zS!et3TQdWO(9rJLXv#XUdZzE!;;yRW>0s=azy8ZCg%;P zx7=rL;2}R2n);2~Uyfk7NCbJq}HDlWp-uen1o5L}X5M6Ex9H zXb90w&_p+prXacrn&>8W7DeYk6J5e75wUZii7vq;6gvl+*c%+RjC;%+7T-#Ih$xN3 zq@jr}fhM|SL;j@56>n*a9Pn61oR=JaI8)Gv6`vX8^gM9h=s zdnBF6_av{Ba=Pws?8KU2b=}7t7hM8PbP2h?qD!EOPs|pY>JoC3W$Z~8kg;cPR>pqG zR-*KS({7Q*c7=>RZiS4!Z6pd-&fTHeVUm=SGYFI`uY7tvM8b-+nJ4nJ&64}Z_n4Vd zue}Zv^rUUJDNW+{Y*mVH3Qc?=jxkHT9h%Nn9*xm{$lW3kI3yd}hr6IO$t?p*08p@! zOH4U?yfKUmzP*eKQz4coLfG9L@D(3?wfN z8U~Dvi<}W7(NBFBXkrhMaw7H+H1S>V=)`w{CiW0p;9?I!lQ{K;J#`ruIxKSwu=JNb zb&)mp)J3jHnGhKwv?=mJ_*rBFH7RnyR=)6@GfvtMPUl7*;r>cL2vJBswwjxQhLAWl zyQ>nXh9-NO42#66p-G&Y)L)5HLsMOc%dY+4i_%{@qBPZYY_SMG2=fa+SdN4rTaAa2 zMxpi#M=peKgc%ZAQcmMxc05_J8V@6Co0QXd7$TXJOYAWA-nCwhhml2_l+$<^Ct8zo z$(q9Umhgj+zVMB7IGJy3ONtzHI89MD*n1bbvW#FUr~4^HGSn_keEZ~_q3yz|Enr!s zQg3-m$J+vgo1||f_G#ZFPoH{qKLwiFNVpopbJUQ`1zbeok=}1cy>iagXsRa(0Z8At zqeuEiVxRCW$w5O+s?AEmp6E_4MUehlW;7=_D#+LaA1W= zDBnY%g{HB{4SVm}H$q*4)xCGZ#ZnHMd~d6Fm2lFiyo>E*m*q(8Cd;jjV+Bp@H9R`8 z|DZ`6iEy^~h!*0GV`W!`B{b1ZXfRm=powlGt3`AZG|^2&*F-l#6WxS0F1pFm;i4Sy zD7~zq&}6M;Wt24;nylTN7?m|1n%DwlRmt8qG_ft%HV_*Gn%F8F>=m2F4gg0v#VipU z37XhaTOJ#Z^Aeiq95OIO=RgykL%z4@9B5)YCg;F84aTN_m~WU;lACAe#iM@VY^nJ1 z(8S-jl-{U2p-KFJ6+moxXyO~d4e=q&)YEe-e-7WTe=M(8Nw;J5+TxCc4Zm zLP0XO2yV*UvfyECbCSzWL{)V*!62Di1XdE7*ps$}EAtJ%TV&E4OlhCoBe%!XkXR%% z+5cd7OYB5wVkdGXk=TjQ#7<_l!17CRA|*omZ%i=7Bf_M^624noFpA?;t} zkK=E`4-+iGYFrAbmpB*M)Dq`{mXy=jI`;APZ$`4YMl5)xq)NWEv`N7C1<&+;}%_ZfOA9(CZIpqgwRa%ZS%Q6PI6-rC^u}JvA zy#|U+__0X%!Ctvy6MiIn6Q7AwR1zUg9C3l}dll#YwmV6JVJ=VKa-;cDpq@3n1a1tOXr#ZcLBu?v&)4;epslfh0~iSGWgzlMN&?4dpISWl;f0a>>H_X2`wq7dwfK_lXB{d+tqi`&gRM*iHky$ zxTswsB=T$*21!5kj1C#X;$vgBi;oRWd~A-d%AO50$wTQ9UmTjmPc7Y6^myWnbDx{U zPoYWtlMV{FMk1+)@L?nI+P2#6$FxjJrCh=1u@De|TCcZfCk@(`! zB+hDAB?`|87%NTls<;YCeDMxnT-Hm1WHFY(-N)javPCMsBsA5p$da^~>vNPQ zZ_@19j!(+TU9pr~CgtSLLdvZq21T?^=Mfj)h&+>0p3stVnnOhjK~j#@BFY*^X_cmX zuDtOjIbN_x<%J7)<$I*VCA6d*n{BauNiMq`bI@{J+b`HeUy;kMTdKK#w*>t~y1Uww_g*nRWtYtCNpzFzL0J^kjJ zr%%4vbkFc_xZ`rY`HCaw+ub)`eZ?_ayR_`2N>Dz{q&Q6 N_=n&8;hRrC`TvrA#zX)B literal 0 HcmV?d00001 diff --git a/Resources/database.xml b/Resources/database.xml index 3257dc9..52828fd 100644 --- a/Resources/database.xml +++ b/Resources/database.xml @@ -1,18 +1,39 @@ + + 0013A20040D8CA1E - 0013A200415278B8 + 0013A200415278B8 0013A2004103B363 0013A200415278AD - 0013A2004103B356 + 0013A2004103B356 0013A200415278B7 0013A2004098A7A7 0013A2004098A7BA - 0013A200415A9DDD + 0013A200415A9DDD 0013A200415A9DE4 0013A200415A9DDF 0013A200415A9DDE - 0013A200415A9DE8 - + 0013A200415A9DE8 + 0013A2004156FA60 + 0013A2004156FA61 + 0013A2004156FA57 + 0013A200417DFE1D + 0013A200417DFE2B + 0013A200417DFE04 + 0013A20041795D68 + 0013A20041795E68 + 0013A2004178AF0E + + 0013A20041795D68 + 0013A20041795E68 + 0013A2004178AF0E diff --git a/include/CommunicationManager.h b/include/CommunicationManager.h index 74dbfba..2398083 100644 --- a/include/CommunicationManager.h +++ b/include/CommunicationManager.h @@ -1,113 +1,103 @@ /* CommunicationManager.h -- Communication Manager class for XBee: - Handles all communications with other ROS nodes - and the serial port -- */ + Handles all communications with other ROS nodes + and the serial port -- */ /* ------------------------------------------------------------------------- */ /* September 20, 2016 -- @Copyright Aymen Soussia. All rights reserved. */ /* (aymen.soussia@gmail.com) */ - #pragma once +#include "PacketsHandler.h" +#include "SerialDevice.h" #include -#include -#include -#include -#include -#include -#include +#include +#include +#include #include #include -#include"PacketsHandler.h" -#include"SerialDevice.h" +#include +#include +#include +namespace Mist { -namespace Mist -{ - - -namespace Xbee -{ - +namespace Xbee { //***************************************************************************** -struct Waypoint_S -{ - unsigned int latitude; - unsigned int longitude; - double altitude; - unsigned int staytime; - unsigned int heading; +struct Waypoint_S { + unsigned int latitude; + unsigned int longitude; + double altitude; + unsigned int staytime; + unsigned int heading; }; - //***************************************************************************** class CommunicationManager { -public: - CommunicationManager(); - ~CommunicationManager(); + public: + CommunicationManager(); + ~CommunicationManager(); - enum class DRONE_TYPE {MASTER, SLAVE}; - enum class RUNNING_MODE {SWARM, SOLO}; + enum class DRONE_TYPE { MASTER, SLAVE }; + enum class RUNNING_MODE { SWARM, SOLO }; - bool Init(const std::string& device, const std::size_t baud_rate); - void Run(DRONE_TYPE drone_type, RUNNING_MODE running_mode); + bool Init(const std::string &device, const std::size_t baud_rate); + void Run(DRONE_TYPE drone_type, RUNNING_MODE running_mode); -private: + private: + const unsigned char START_DLIMITER; + const std::size_t LOOP_RATE; + const uint8_t DEFAULT_RATE_DIVIDER_RSSI; + const uint8_t DEFAULT_RATE_DIVIDER_PACKET_LOSS; + const uint16_t DEFAULT_RSSI_PAYLOAD_SIZE; + const uint16_t DEFAULT_RSSI_ITERATIONS; - const unsigned char START_DLIMITER; - const std::size_t LOOP_RATE; + void Run_In_Solo_Mode(DRONE_TYPE drone_type); + void Run_In_Swarm_Mode(); + void Display_Init_Communication_Failure(); + void Send_Mavlink_Message_Callback( + const mavros_msgs::Mavlink::ConstPtr &mavlink_msg); + void Display_Drone_Type_and_Running_Mode(DRONE_TYPE drone_type, + RUNNING_MODE running_mode); + bool Serve_Flight_Controller(mavros_msgs::CommandInt::Request &request, + mavros_msgs::CommandInt::Response &response); + void Check_In_Messages_and_Transfer_To_Server(); + void Process_In_Standard_Messages(); + void Process_In_Acks_and_Pings(); + void Process_In_Fragments(); + void Process_In_Packets(); + void Process_Command_Responses(); + void Process_Packet_Loss(); + bool Get_Param(mavros_msgs::ParamGet::Request &req, + mavros_msgs::ParamGet::Response &res); + bool getRosParams(); + int getIntParam(std::string name, int default_value); + void triggerRssiUpdate(); + std::string safeSubStr(const std::string strg, + const unsigned int index_max) const; - void Run_In_Solo_Mode(DRONE_TYPE drone_type); - void Run_In_Swarm_Mode(); - /*void Generate_Transmit_Request_Frame( - const char* const message, - std::string* frame, - const unsigned char frame_ID = - static_cast(0x01), - const std::string& destination_adssress = "000000000000FFFF", - const std::string& short_destination_adress = "FFFF", - const std::string& broadcast_radius = "00", - const std::string& options = "00");*/ - //void Check_In_Messages_and_Transfer_To_Topics(); - void Display_Init_Communication_Failure(); - //void Convert_HEX_To_Bytes(const std::string& HEX_data, - //std::string* converted_data); - //void Calculate_and_Append_Checksum(std::string* frame); - //void Add_Length_and_Start_Delimiter(std::string* frame); - void Send_Mavlink_Message_Callback( - const mavros_msgs::Mavlink::ConstPtr& mavlink_msg); - void Display_Drone_Type_and_Running_Mode(DRONE_TYPE drone_type, - RUNNING_MODE running_mode); - bool Serve_Flight_Controller(mavros_msgs::CommandInt:: - Request& request, mavros_msgs::CommandInt::Response& response); - void Check_In_Messages_and_Transfer_To_Server(); - void Process_In_Standard_Messages(); - void Process_In_Acks_and_Pings(); - void Process_In_Fragments(); - void Process_In_Packets(); - void Process_Command_Responses(); - bool Get_Param(mavros_msgs::ParamGet::Request& req, mavros_msgs::ParamGet::Response& res); - - Mist::Xbee::SerialDevice serial_device_; - Mist::Xbee::PacketsHandler packets_handler_; - Thread_Safe_Deque in_std_messages_; - Thread_Safe_Deque in_fragments_; - Thread_Safe_Deque in_Acks_and_Pings_; - Thread_Safe_Deque command_responses_; - Thread_Safe_Deque in_packets_; - ros::NodeHandle node_handle_; - ros::Subscriber mavlink_subscriber_; - ros::Publisher mavlink_publisher_; - ros::ServiceClient mav_dji_client_; - ros::ServiceServer mav_dji_server_; - ros::ServiceServer StatusSrv_; - std_msgs::UInt8 device_id_out; - std::shared_ptr service_thread_; // TO DO delete !? + Mist::Xbee::SerialDevice serial_device_; + Mist::Xbee::PacketsHandler packets_handler_; + Thread_Safe_Deque in_std_messages_; + Thread_Safe_Deque in_fragments_; + Thread_Safe_Deque in_Acks_and_Pings_; + Thread_Safe_Deque command_responses_; + Thread_Safe_Deque in_packets_; + Thread_Safe_Deque in_packet_loss_; + ros::NodeHandle node_handle_; + ros::Subscriber mavlink_subscriber_; + ros::Publisher mavlink_publisher_; + ros::ServiceClient mav_dji_client_; + ros::ServiceServer mav_dji_server_; + ros::ServiceServer StatusSrv_; + std_msgs::UInt8 device_id_out; + std::shared_ptr service_thread_; // TO DO delete !? + std::uint16_t packet_loss_timer_; + uint8_t rate_divider_rssi_; + uint8_t rate_divider_packet_loss_; + uint16_t rssi_payload_size_; + uint16_t rssi_iterations_; }; - - } - - } diff --git a/include/PacketsHandler.h b/include/PacketsHandler.h index 178cea9..d092f4b 100644 --- a/include/PacketsHandler.h +++ b/include/PacketsHandler.h @@ -1,6 +1,6 @@ /* PacketsHandler.h-- Packets Handler class for XBee: - Serialize, deserialize, fragment and reassemly mavlink - messages -- */ + Serialize, deserialize, fragment and reassemly mavlink + messages -- */ /* ------------------------------------------------------------------------- */ /* February 06, 2017 -- @Copyright Aymen Soussia. All rights reserved. */ /* (aymen.soussia@gmail.com) */ @@ -8,23 +8,24 @@ #pragma once -#include -#include -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include +#include +#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include -#include"MultithreadingDeque.hpp" -#include"SerialDevice.h" +#include "MultithreadingDeque.hpp" +#include "SerialDevice.h" +#include "frame_generators.h" //***************************************************************************** @@ -38,114 +39,160 @@ namespace Mist namespace Xbee { + struct Reassembly_Packet_S + { + uint8_t packet_ID_; + std::string packet_buffer_; // TO DO make it shared ptr + std::set received_fragments_IDs_; + std::clock_t time_since_creation_; // TO DO use it to delete packets with time out + }; -//***************************************************************************** -class PacketsHandler -{ -public: - PacketsHandler(); - ~PacketsHandler(); - - bool Init(SerialDevice* serial_device, Thread_Safe_Deque* in_packets); - bool Init_Device_ID(); - void Run(); - void Handle_Mavlink_Message(const mavros_msgs::Mavlink::ConstPtr& mavlink_msg); - void Process_Fragment(std::shared_ptr fragment); - void Process_Ping_Or_Acknowledgement(std::shared_ptr frame); - void Process_Command_Response(const char* command_response); - void Quit(); - void Delete_Packets_With_Time_Out(); - void Deserialize_Mavlink_Message(const char * bytes, - mavros_msgs::Mavlink* mavlink_msg, const std::size_t msg_size); - uint8_t get_device_id(); - - -private: - const std::size_t MAX_PACEKT_SIZE; /* MAX packet size in bytes = 63750 bytes */ - const std::size_t XBEE_NETWORK_MTU; /* Maximum Transmission Unit of Xbee netwrok = 256 bytes (max payload) - 6 bytes (Header size of each fragment) = 250 bytes */ - const std::size_t FRAGMENT_HEADER_SIZE; /* Header size of each fragment = 6 bytes */ - const std::clock_t MAX_TIME_TO_SEND_PACKET; /* Maximum time before dropping a packet = 30 seconds*/ - const unsigned char START_DLIMITER; - - struct Reassembly_Packet_S - { - uint8_t packet_ID_; - std::string packet_buffer_; // TO DO make it shared ptr - std::set received_fragments_IDs_; - std::clock_t time_since_creation_; // TO DO use it to delete packets with time out - }; - - void Insert_Fragment_In_Packet_Buffer(std::string* buffer, - const char* fragment, const uint16_t offset, const std::size_t length); - void Add_New_Node_To_Network(const uint8_t new_node_address); - void Serialize_Mavlink_Message(const mavros_msgs::Mavlink::ConstPtr& - mavlink_msg, std::shared_ptr serialized_packet); - void Insert_Fragment_Header(bool single_fragment, - std::shared_ptr fragment, const uint8_t packet_ID, - const uint8_t fragment_ID, const uint16_t offset); - void Process_Out_Standard_Messages(); - void Process_Out_Packets(); - void Send_Packet(const Out_Packet_S& packet); - void Send_End_Of_Packet_Ping(const uint8_t packet_ID, const uint8_t total_NBR_of_fragments); - bool Load_Database_Addresses(); - bool Get_Local_Address(); - bool Check_Packet_Transmitted_To_All_Nodes(); - void Init_Network_Nodes_For_New_Transmission(const uint8_t packet_ID, - std::vector* frames, - std::shared_ptr>> packet); - void Transmit_Fragments(const std::vector& frames); - void Adjust_Optimum_MT_Number(const std::clock_t elapsed_time, - const std::size_t NBR_of_transmission); - void Send_SL_and_SH_Commands(); - void Generate_Transmit_Request_Frame( - const char* message, - std::string* frame, - const std::size_t message_size, - const unsigned char frame_ID = - static_cast(0x01), - const std::string& destination_adssress = "000000000000FFFF", - const std::string& short_destination_adress = "FFFF", - const std::string& broadcast_radius = "00", - const std::string& options = "00"); - void Convert_HEX_To_Bytes(const std::string& HEX_data, - std::string* converted_data); - void Calculate_and_Append_Checksum(std::string* frame); - void Add_Length_and_Start_Delimiter(std::string* frame); - void Generate_AT_Command(const char* command, - std::string* frame, - const unsigned char frame_ID = - static_cast(0x01)); - - - struct On_Line_Node_S - { - bool received_hole_packet_; - std::string address_64_bits_; - }; - - std::set fragments_indexes_to_transmit_; - SerialDevice* serial_device_; - std::atomic quit_; - Thread_Safe_Deque out_std_messages_; - Thread_Safe_Deque_Of_Vectors out_packets_; - Thread_Safe_Deque* in_packets_; - std::map connected_network_nodes_; - std::map::iterator connected_network_nodes_it_; - std::map packets_assembly_map_; - std::map::iterator assembly_map_it_; - std::map database_addresses_; - std::map::iterator database_addresses_it_; - std::mutex mutex_; - uint8_t device_address_; - std::string device_64_bits_address_; - bool loaded_SL_; - bool loaded_SH_; - uint8_t current_processed_packet_ID_; - std::size_t optimum_MT_NBR_; - // TO DO & after auto !? - useconds_t delay_interframes_; -}; + struct On_Line_Node_S + { + uint64_t device_64_bits_address_; + float packet_loss_raw_; + float packet_loss_filtered_; + uint16_t sent_packets_; + uint16_t received_packets_; + uint8_t packet_loss_sent_id_; + uint8_t packet_loss_received_id_; + }; + enum RSSI_API_STATUS + { + OLD_VALUE, + TRIGGERED, + NEW_VALUE + }; + + struct RSSI_Result + { + uint16_t payload_size; + uint16_t iterations; + uint16_t success; + uint16_t retries; + uint8_t result; + uint8_t rr; + uint8_t max_rssi; + uint8_t min_rssi; + uint8_t avg_rssi; + RSSI_API_STATUS status; + }; + + //***************************************************************************** + class PacketsHandler + { + public: + PacketsHandler(); + ~PacketsHandler(); + + bool Init(SerialDevice* serial_device, Thread_Safe_Deque* in_packets); + bool Init_Device_ID(); + void Run(); + void Handle_Mavlink_Message(const mavros_msgs::Mavlink::ConstPtr& mavlink_msg); + void Process_Fragment(std::shared_ptr fragment); + void Process_Ping_Or_Acknowledgement(std::shared_ptr frame); + void Process_Command_Response(const char* command_response); + void Quit(); + void Delete_Packets_With_Time_Out(); + void Deserialize_Mavlink_Message(const char * bytes, + mavros_msgs::Mavlink* mavlink_msg, const std::size_t msg_size); + uint8_t getDeviceId(); + uint8_t getDequeFull(); + float getSignalStrength(); + float getAPISignalStrength(uint8_t short_node_id); + float getRawPacketLoss(uint8_t short_node_id); + float getPacketLoss(uint8_t short_node_id); + void triggerRssiUpdate(); + uint8_t triggerAPIRssiUpdate(uint16_t rssi_payload_size, + uint16_t rssi_iterations, + uint8_t target_id); + void processPacketLoss(const char* packet_loss); + void sendPacketLoss(); + + static uint16_t ucharToUint16(unsigned char msb, unsigned char lsb); + + static const uint16_t PACKET_LOSS_UNAVAILABLE; + static const uint8_t ALL_IDS; + static const uint8_t MAX_WAITING_OUT_MSG; + + private: + const std::size_t MAX_PACEKT_SIZE; /* MAX packet size in bytes = 63750 bytes */ + const std::size_t XBEE_NETWORK_MTU; /* Maximum Transmission Unit of Xbee netwrok = 256 bytes (max payload) - 6 bytes (Header size of each fragment) = 250 bytes */ + const std::size_t FRAGMENT_HEADER_SIZE; /* Header size of each fragment = 6 bytes */ + const std::clock_t MAX_TIME_TO_SEND_PACKET; /* Maximum time before dropping a packet = 30 seconds*/ + ; + // RSSI constants + const std::string RSSI_COMMAND; + const float RSSI_FILTER_GAIN; //filter: old * (1.0-GAIN) + new * GAIN + + // Packet Loss + const std::string PACKET_LOSS_IDENTIFIER; + const uint8_t MAX_PACKET_LOSS_MSG_ID; // used for synchronisation + const float PACKET_LOSS_FILTER_GAIN; //filter: new * (1.0-GAIN) + old * GAIN + + void Insert_Fragment_In_Packet_Buffer(std::string* buffer, + const char* fragment, const uint16_t offset, const std::size_t length); + void Add_New_Node_To_Network(const uint8_t new_node_address); + void Serialize_Mavlink_Message(const mavros_msgs::Mavlink::ConstPtr& + mavlink_msg, std::shared_ptr serialized_packet); + void Insert_Fragment_Header(bool single_fragment, + std::shared_ptr fragment, const uint8_t packet_ID, + const uint8_t fragment_ID, const uint16_t offset); + void Process_Out_Standard_Messages(); + void Process_Out_Packets(); + void Send_Packet(const Out_Packet_S& packet); + void Send_End_Of_Packet_Ping(const uint8_t packet_ID, const uint8_t total_NBR_of_fragments); + bool Load_Database_Addresses(); + bool Get_Local_Address(); + bool Check_Packet_Transmitted_To_All_Nodes(); + void Init_Network_Nodes_For_New_Transmission(const uint8_t packet_ID, + std::vector* frames, + std::shared_ptr > > packet); + void Transmit_Fragments(const std::vector& frames); + void Adjust_Optimum_MT_Number(const std::clock_t elapsed_time, + const std::size_t NBR_of_transmission); + void Send_SL_and_SH_Commands(); + + + float computePercentage(const int16_t numerator, const int16_t denumerator) const; + float filterIIR(const float new_val, const float old_val, const float gain) const; + void updatePacketLoss(On_Line_Node_S& node, const uint16_t recieved_packet); + void processAPIRssi(const char* command_response); + uint64_t get64BitsAddress(const char* bytes, const int offset); + + std::set fragments_indexes_to_transmit_; + SerialDevice* serial_device_; + std::atomic quit_; + Thread_Safe_Deque out_std_messages_; + Thread_Safe_Deque_Of_Vectors out_packets_; + Thread_Safe_Deque* in_packets_; + std::map connected_network_nodes_; + std::map::iterator connected_network_nodes_it_; + std::map packets_assembly_map_; + std::map::iterator assembly_map_it_; + std::map database_addresses_; + std::map::iterator database_addresses_it_; + std::map database_addresses_inv_; + std::map::iterator database_addresses_inv_it_; + std::map packet_loss_map_; + std::map::iterator packet_loss_it_; + std::map rssi_result_map_; + std::map::iterator rssi_result_map_it_; + + std::mutex mutex_; + uint8_t device_address_; + uint64_t local_64_bits_address_; + std::string device_64_bits_address_; + bool loaded_SL_; + bool loaded_SH_; + bool deque_full_; + float rssi_float_; + uint8_t current_processed_packet_ID_; + std::size_t optimum_MT_NBR_; + // TO DO & after auto !? + useconds_t delay_interframes_; + }; } diff --git a/include/SerialDevice.h b/include/SerialDevice.h index 25333cf..5f842e7 100644 --- a/include/SerialDevice.h +++ b/include/SerialDevice.h @@ -9,7 +9,7 @@ #include #include -#include +#include #include @@ -49,11 +49,18 @@ public: void Set_In_Messages_Pointers(Thread_Safe_Deque* in_std_messages, Thread_Safe_Deque* in_fragments, Thread_Safe_Deque* in_Acks_and_Pings, - Thread_Safe_Deque* command_responses); + Thread_Safe_Deque* command_responses, + Thread_Safe_Deque* in_packet_loss); bool Is_IO_Service_Stopped(); // TO DO delete this function void Reset_IO_Service(); // TO DO delete this function void Close_Serial_Port(); + const char FRAGMENT_MSG_ID = 'F'; + const char ACKNOWLEDGEMENT_MSG_ID = 'A'; + const char PING_MSG_ID = 'P'; + const char STANDARD_MSG_ID = 'S'; + const char PACKET_LOSS_MSG_ID = 'L'; + private: enum FRAME_TYPE @@ -88,6 +95,8 @@ private: Thread_Safe_Deque* in_fragments_; Thread_Safe_Deque* in_Acks_and_Pings_; Thread_Safe_Deque* command_responses_; + Thread_Safe_Deque* in_packet_loss_; + Mist::Xbee::Frame current_frame_; unsigned int FRAME_TYPE_KEYS[REMOTE_AT_COMMAND_RESPONSE + 1]; }; diff --git a/include/XBeeSetup.h b/include/XBeeSetup.h new file mode 100644 index 0000000..a0bf995 --- /dev/null +++ b/include/XBeeSetup.h @@ -0,0 +1,14 @@ +/* ---------------------------------------------------------------- + * File: XBeeSetup.cpp + * Date: 02/06/2017 + * Author: Pierre-Yves Breches + * Description: Implementation of the xbeeSetup function to + * configure the xbee module + * Copyright Humanitas Solutions. All rights reserved. + ------------------------------------------------------------------ */ +#include + +#include"XBeeModule.h" +#include"XMLConfigParser.h" + +bool setupXBee(const std::string& device_port, const unsigned int baud_rate); diff --git a/include/frame_generators.h b/include/frame_generators.h new file mode 100644 index 0000000..a045e4e --- /dev/null +++ b/include/frame_generators.h @@ -0,0 +1,59 @@ +/* ---------------------------------------------------------------- + * File: frame_generators.h + * Created on: 21/06/2017 + * Author: Pierre-Yves Breches + * Description: This file contains functions used for the the creation of xbee + * frame + * Copyright Humanitas Solutions. All rights reserved. + ------------------------------------------------------------------ */ + +#include +#include +#include +#include +#include + +namespace Mist +{ + +namespace Xbee +{ + + void Generate_Transmit_Request_Frame( + const char* message, + std::string* frame, + const std::size_t message_size, + const unsigned char frame_ID = static_cast(0x01), + const std::string& destination_adssress = "000000000000FFFF", + const std::string& short_destination_adress = "FFFF", + const std::string& broadcast_radius = "00", + const std::string& options = "00"); + + void generateLinkTestingFrame( + std::string* frame, + uint16_t rssi_payload_size, + uint16_t rssi_iterations, + std::string device_64_bits_address, + uint64_t target_64_bits_address); + + void Generate_AT_Command(const char* command, + std::string* frame, + const unsigned char frame_ID = + static_cast(0x01)); + + void Convert_HEX_To_Bytes(const std::string& HEX_data, + std::string* converted_data); + void Calculate_and_Append_Checksum(std::string* frame); + void Add_Length_and_Start_Delimiter(std::string* frame); + + template< typename T > + std::string int_to_hex(const T i, int size) + { + std::stringstream stream; + stream << std::setfill ('0') << std::setw(size) + << std::hex << i; + return stream.str(); + } +} + +} diff --git a/launch/xbeemav.launch b/launch/xbeemav.launch index 4d789ce..5698534 100644 --- a/launch/xbeemav.launch +++ b/launch/xbeemav.launch @@ -1,4 +1,5 @@ + @@ -9,6 +10,7 @@ - + + diff --git a/launch/xbeemav_test.launch b/launch/xbeemav_test.launch new file mode 100644 index 0000000..0ae3cd6 --- /dev/null +++ b/launch/xbeemav_test.launch @@ -0,0 +1,27 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/src/CommunicationManager.cpp b/src/CommunicationManager.cpp index 3f1156d..4fc86a5 100644 --- a/src/CommunicationManager.cpp +++ b/src/CommunicationManager.cpp @@ -1,26 +1,32 @@ /* CommunicationManager.cpp -- Communication Manager class for XBee: - Handles all communications with other ROS nodes - and the serial port -- */ + Handles all communications with other ROS nodes + and the serial port -- */ /* ------------------------------------------------------------------------- */ /* September 20, 2016 -- @Copyright Aymen Soussia. All rights reserved. */ /* (aymen.soussia@gmail.com) */ - - +/* ------------------------------------------------------------------------- */ +/* Revision + * Date: July 1st, 2017 + * Author: Pierre-Yves Breches + */ +/* ------------------------------------------------------------------------- */ #include "CommunicationManager.h" namespace Mist { - namespace Xbee { - //***************************************************************************** -CommunicationManager::CommunicationManager(): - START_DLIMITER(static_cast(0x7E)), - LOOP_RATE(10) /* 10 fps */ +CommunicationManager::CommunicationManager() : + START_DLIMITER(static_cast(0x7E)), + LOOP_RATE(10), /* 10 fps */ + DEFAULT_RATE_DIVIDER_RSSI(5), + DEFAULT_RATE_DIVIDER_PACKET_LOSS(20), + DEFAULT_RSSI_PAYLOAD_SIZE(10), + DEFAULT_RSSI_ITERATIONS(2) { } @@ -32,106 +38,106 @@ CommunicationManager::~CommunicationManager() //***************************************************************************** -bool CommunicationManager::Init( - const std::string& device, const std::size_t baud_rate) +bool CommunicationManager::Init(const std::string& device, + const std::size_t baud_rate) { - if (serial_device_.Init(device, baud_rate)) - { - serial_device_.Set_In_Messages_Pointers(&in_std_messages_, &in_fragments_, - &in_Acks_and_Pings_, &command_responses_); - - service_thread_ = std::make_shared(std::thread(&SerialDevice::Run_Service, &serial_device_)); - - if (!packets_handler_.Init(&serial_device_, &in_packets_)) - return false; - - std::clock_t elapsed_time = std::clock(); - bool device_ID_loaded = false; - - while (std::clock() - elapsed_time <= 300000) - { - Process_Command_Responses(); - - if (packets_handler_.Init_Device_ID()) - { - device_ID_loaded = true; - break; - } - } - - if (!device_ID_loaded) - return false; - } - else - { - Display_Init_Communication_Failure(); - return false; - } - - return true; + if (serial_device_.Init(device, baud_rate)) + { + serial_device_.Set_In_Messages_Pointers(&in_std_messages_, &in_fragments_, + &in_Acks_and_Pings_, &command_responses_, + &in_packet_loss_); + + service_thread_ = std::make_shared(std::thread(&SerialDevice::Run_Service, &serial_device_)); + + if (!packets_handler_.Init(&serial_device_, &in_packets_)) + return false; + + std::clock_t elapsed_time = std::clock(); + bool device_ID_loaded = false; + + while (std::clock() - elapsed_time <= 300000) + { + Process_Command_Responses(); + + if (packets_handler_.Init_Device_ID()) + { + device_ID_loaded = true; + break; + } + } + + if (!device_ID_loaded) + return false; + } + else + { + Display_Init_Communication_Failure(); + return false; + } + + return true; } //***************************************************************************** void CommunicationManager::Run(DRONE_TYPE drone_type, - RUNNING_MODE running_mode) + RUNNING_MODE running_mode) { - std::thread thread_packets_handler(&PacketsHandler::Run, &packets_handler_); + std::thread thread_packets_handler(&PacketsHandler::Run, &packets_handler_); - Display_Drone_Type_and_Running_Mode(drone_type, running_mode); + Display_Drone_Type_and_Running_Mode(drone_type, running_mode); - if (RUNNING_MODE::SWARM == running_mode) - Run_In_Swarm_Mode(); - else - Run_In_Solo_Mode(drone_type); + if (RUNNING_MODE::SWARM == running_mode) + Run_In_Swarm_Mode(); + else + Run_In_Solo_Mode(drone_type); - serial_device_.Stop_Service(); - serial_device_.Close_Serial_Port(); - packets_handler_.Quit(); - service_thread_->join(); - thread_packets_handler.join(); + serial_device_.Stop_Service(); + serial_device_.Close_Serial_Port(); + packets_handler_.Quit(); + service_thread_->join(); + thread_packets_handler.join(); } //***************************************************************************** void CommunicationManager::Run_In_Solo_Mode(DRONE_TYPE drone_type) { - std::string service_name; - bool success = false; + std::string service_name; + bool success = false; - if (DRONE_TYPE::MASTER == drone_type) - { - if (node_handle_.getParam("Xbee_In_From_Controller", service_name)) - { - mav_dji_server_ = node_handle_.advertiseService(service_name.c_str(), &CommunicationManager::Serve_Flight_Controller, this); - success = true; - } - else - std::cout << "Failed to Get Service Name: param 'Xbee_In_From_Controller' Not Found." << std::endl; - } - else - { - if (node_handle_.getParam("Xbee_Out_To_Controller", service_name)) - { - mav_dji_client_ = node_handle_.serviceClient(service_name.c_str()); - success = true; - } - else - std::cout << "Failed to Get Service Name: param 'Xbee_Out_To_Controller' Not Found." << std::endl; - } + if (DRONE_TYPE::MASTER == drone_type) + { + if (node_handle_.getParam("Xbee_In_From_Controller", service_name)) + { + mav_dji_server_ = node_handle_.advertiseService(service_name.c_str(), &CommunicationManager::Serve_Flight_Controller, this); + success = true; + } + else + std::cout << "Failed to Get Service Name: param 'Xbee_In_From_Controller' Not Found." << std::endl; + } + else + { + if (node_handle_.getParam("Xbee_Out_To_Controller", service_name)) + { + mav_dji_client_ = node_handle_.serviceClient(service_name.c_str()); + success = true; + } + else + std::cout << "Failed to Get Service Name: param 'Xbee_Out_To_Controller' Not Found." << std::endl; + } - if (success) - { - ros::Rate loop_rate(LOOP_RATE); + if (success) + { + ros::Rate loop_rate(LOOP_RATE); - while (ros::ok()) - { - Check_In_Messages_and_Transfer_To_Server(); - ros::spinOnce(); - loop_rate.sleep(); - } - } + while (ros::ok()) + { + ros::spinOnce(); + loop_rate.sleep(); + } + } } @@ -139,423 +145,389 @@ void CommunicationManager::Run_In_Solo_Mode(DRONE_TYPE drone_type) //***************************************************************************** void CommunicationManager::Run_In_Swarm_Mode() { - std::string out_messages_topic; - std::string in_messages_topic; - bool success_1 = false; - bool success_2 = false; - StatusSrv_ = node_handle_.advertiseService("/xbee_status", &CommunicationManager::Get_Param, this); - if (node_handle_.getParam("Xbee_In_From_Buzz", out_messages_topic)) - { - mavlink_subscriber_ = node_handle_.subscribe(out_messages_topic.c_str(), 1000, - &CommunicationManager::Send_Mavlink_Message_Callback, this); - success_1 = true; - } - else - std::cout << "Failed to Get Topic Name: param 'Xbee_In_From_Buzz' Not Found." << std::endl; - if (node_handle_.getParam("Xbee_Out_To_Buzz", in_messages_topic)) - { - mavlink_publisher_ = node_handle_.advertise( - in_messages_topic.c_str(), 1000); - success_2 = true; - } - else - std::cout << "Failed to Get Topic Name: param 'Xbee_Out_To_Buzz' Not Found." << std::endl; + if (getRosParams()) + { - if (success_1 && success_2) - { + ros::Rate loop_rate(LOOP_RATE); - ros::Rate loop_rate(LOOP_RATE); - while (ros::ok()) - { - Process_In_Standard_Messages(); - Process_In_Fragments(); - Process_In_Acks_and_Pings(); - Process_In_Packets(); - packets_handler_.Delete_Packets_With_Time_Out(); - ros::spinOnce(); - loop_rate.sleep(); - } - } + while (ros::ok()) + { + triggerRssiUpdate(); + Process_In_Standard_Messages(); + Process_In_Fragments(); + Process_In_Acks_and_Pings(); + Process_In_Packets(); + Process_Packet_Loss(); + Process_Command_Responses(); + packets_handler_.Delete_Packets_With_Time_Out(); + ros::spinOnce(); + loop_rate.sleep(); + } + } } //***************************************************************************** inline bool CommunicationManager::Serve_Flight_Controller(mavros_msgs::CommandInt:: - Request& request, mavros_msgs::CommandInt::Response& response) + Request& request, mavros_msgs::CommandInt::Response& response) // TODO to be cleaned { - const std::size_t MAX_BUFFER_SIZE = 256; - unsigned int command = 0; - char temporary_buffer[MAX_BUFFER_SIZE]; - std::string frame; - - /*switch(request.command) - { - case mavros_msgs::CommandCode::NAV_TAKEOFF: - { - command = static_cast(mavros_msgs::CommandCode::NAV_TAKEOFF); - sprintf(temporary_buffer, "%u ", command); - response.success = true; - break; - } - case mavros_msgs::CommandCode::NAV_LAND: - { - command = static_cast(mavros_msgs::CommandCode::NAV_LAND); - sprintf(temporary_buffer, "%u ", command); - response.success = true; - break; - } - case mavros_msgs::CommandCode::NAV_RETURN_TO_LAUNCH: - { - command = static_cast(mavros_msgs::CommandCode::NAV_RETURN_TO_LAUNCH); - sprintf(temporary_buffer, "%u ", command); - response.success = true; - break; - } - case mavros_msgs::CommandCode::NAV_WAYPOINT: - { - command = static_cast(mavros_msgs::CommandCode::NAV_WAYPOINT); - sprintf(temporary_buffer, "%u %u %u %lf %u %u ", - command, request.x, request.y, request.z, 0, 1); // TO DO change 0 and 1 - response.success = true; - break; - } - case mavros_msgs::CommandCode::CMD_MISSION_START: - { - command = static_cast(mavros_msgs::CommandCode::CMD_MISSION_START); - sprintf(temporary_buffer, "%u ", command); - response.success = true; - break; - } - default: - response.success = false; - } - - if (command != 0) - { - Generate_Transmit_Request_Frame(temporary_buffer, &frame); - serial_device_.Send_Frame(frame); - }*/ - - return true; + return true; } //***************************************************************************** void CommunicationManager::Display_Init_Communication_Failure() { - std::cout << "Failed to Init Communication With XBee." << std::endl; - std::cout << "Please Check The Following Parameters:" << std::endl; - std::cout << " 1) Device (e.g. /dev/ttyUSB0 for Linux. " << std::endl; - std::cout << " 2) Baud Rate." << std::endl; - std::cout << " 3) Press Reset Button on The XBee." << std::endl; - std::cout << " 4) Connect and Disconnect The XBee." << std::endl; - std::cout << " 5) Update The XBee Firmware." << std::endl; - std::cout << " 6) Reinstall The FTDI Driver." << std::endl; -} - - -//***************************************************************************** -/*inline void CommunicationManager::Generate_Transmit_Request_Frame( - const char* const message, - std::string * frame, - const unsigned char frame_ID, - const std::string& destination_adssress, - const std::string& short_destination_adress, - const std::string& broadcast_radius, - const std::string& options) -{ - const unsigned char FAME_TYPE = static_cast(0x10); /* Transmit Request Frame */ - /*std::string frame_parameters; - std::string bytes_frame_parameters; - - frame_parameters.append(destination_adssress); - frame_parameters.append(short_destination_adress); - frame_parameters.append(broadcast_radius); - frame_parameters.append(options); - - Convert_HEX_To_Bytes(frame_parameters, &bytes_frame_parameters); - - frame->push_back(FAME_TYPE); - frame->push_back(frame_ID); - frame->append(bytes_frame_parameters); - frame->append(message, std::strlen(message)); - - Calculate_and_Append_Checksum(frame); - Add_Length_and_Start_Delimiter(frame); -}*/ - - -//***************************************************************************** -/*inline void CommunicationManager::Convert_HEX_To_Bytes( - const std::string& HEX_data, std::string* converted_data) -{ - const unsigned short TWO_BYTES = 2; - char temporary_buffer[TWO_BYTES]; - unsigned char temporary_char; - int temporary_HEX; - - for (unsigned short i = 0; i <= HEX_data.size() - TWO_BYTES; - i += TWO_BYTES) - { - memcpy(temporary_buffer, HEX_data.c_str() + i, TWO_BYTES); - sscanf(temporary_buffer, "%02X", &temporary_HEX); - temporary_char = static_cast(temporary_HEX); - converted_data->push_back(temporary_char); - } -}*/ - - -//***************************************************************************** -/*inline void CommunicationManager::Calculate_and_Append_Checksum( - std::string* frame) -{ - unsigned short bytes_sum = 0; - unsigned lowest_8_bits = 0; - unsigned short checksum = 0; - unsigned char checksum_byte; - - for (unsigned short i = 0; i < frame->size(); i++) - bytes_sum += static_cast(frame->at(i)); - - lowest_8_bits = bytes_sum & 0xFF; - checksum = 0xFF - lowest_8_bits; - checksum_byte = static_cast(checksum); - frame->push_back(checksum_byte); -}*/ - - -//***************************************************************************** -/*inline void CommunicationManager::Add_Length_and_Start_Delimiter( - std::string* frame) -{ - const unsigned short FIVE_BYTES = 5; - char temporary_buffer[FIVE_BYTES]; - unsigned char temporary_char; - int Hex_frame_length_1; - int Hex_frame_length_2; - std::string header; - int frame_length = frame->size() - 1; /* frame_length = frame_size - checksum byte */ - - /*header.push_back(START_DLIMITER); - sprintf(temporary_buffer, "%04X", frame_length); - sscanf(temporary_buffer, "%02X%02X", &Hex_frame_length_1, - &Hex_frame_length_2); - temporary_char = static_cast(Hex_frame_length_1); - header.push_back(temporary_char); - temporary_char = static_cast(Hex_frame_length_2); - header.push_back(temporary_char); - frame->insert(0, header); -}*/ - - -//***************************************************************************** -/*inline void CommunicationManager::Check_In_Messages_and_Transfer_To_Topics() // TO DO delete -{ - std::size_t size_in_messages = in_messages_->Get_Size(); - - if (size_in_messages > 0) - { - uint64_t current_int64 = 0; - - for (std::size_t j = 0; j < size_in_messages; j++) - { - std::shared_ptr in_message = - in_messages_->Pop_Front(); - mavros_msgs::Mavlink mavlink_msg; - - for (std::size_t i = 0; i < in_message->size(); i++) - { - if (' ' == in_message->at(i) || 0 == i) - { - sscanf(in_message->c_str() + i, "%" PRIu64 " ", - ¤t_int64); - mavlink_msg.payload64.push_back(current_int64); - } - - } - - mavlink_publisher_.publish(mavlink_msg); - } - - } -}*/ - - -//***************************************************************************** -inline void CommunicationManager::Check_In_Messages_and_Transfer_To_Server() // TO DO change it -{ - //std::size_t size_in_messages = in_messages_->Get_Size(); - - /*if (size_in_messages > 0) - { - for (std::size_t j = 0; j < size_in_messages; j++) - { - std::shared_ptr in_message = - in_messages_->Pop_Front(); - mavros_msgs:: CommandInt command_msg; - unsigned int command = 0; - - sscanf(in_message->c_str(), "%u", &command); - - if (static_cast(mavros_msgs::CommandCode::NAV_WAYPOINT) == command) - { - Waypoint_S new_waypoint; - sscanf(in_message->c_str(), "%u %u %u %lf %u %u ", - &command, &new_waypoint.latitude, - &new_waypoint.longitude, &new_waypoint.altitude, - &new_waypoint.staytime, &new_waypoint.heading); - command_msg.request.x = new_waypoint.latitude; - command_msg.request.y = new_waypoint.longitude; - command_msg.request.z = new_waypoint.altitude; - // TO DO add staytime and heading; - } - - command_msg.request.command = command; - - if (mav_dji_client_.call(command_msg)) - ROS_INFO("XBeeMav: Command Successfully Tranferred to Dji Mav."); - else - ROS_INFO("XBeeMav: Faild to Tranfer Command."); - - } - }*/ + std::cout << "Failed to Init Communication With XBee." << std::endl; + std::cout << "Please Check The Following Parameters:" << std::endl; + std::cout << " 1) Device (e.g. /dev/ttyUSB0 for Linux. " << std::endl; + std::cout << " 2) Baud Rate." << std::endl; + std::cout << " 3) Press Reset Button on The XBee." << std::endl; + std::cout << " 4) Connect and Disconnect The XBee." << std::endl; + std::cout << " 5) Update The XBee Firmware." << std::endl; + std::cout << " 6) Reinstall The FTDI Driver." << std::endl; } //***************************************************************************** inline void CommunicationManager::Send_Mavlink_Message_Callback( - const mavros_msgs::Mavlink::ConstPtr& mavlink_msg) + const mavros_msgs::Mavlink::ConstPtr& mavlink_msg) { - //std::cout << "Received Message From Buzz" << std::endl; // TO DO delete - packets_handler_.Handle_Mavlink_Message(mavlink_msg); + packets_handler_.Handle_Mavlink_Message(mavlink_msg); } //***************************************************************************** void CommunicationManager::Display_Drone_Type_and_Running_Mode( - DRONE_TYPE drone_type, RUNNING_MODE running_mode) + DRONE_TYPE drone_type, RUNNING_MODE running_mode) { - if (DRONE_TYPE::MASTER == drone_type) - std::cout << "Drone: MASTER" << std::endl; - else - std::cout << "Drone: SLAVE" << std::endl; + if (DRONE_TYPE::MASTER == drone_type) + std::cout << "Drone: MASTER" << std::endl; + else + std::cout << "Drone: SLAVE" << std::endl; - if (RUNNING_MODE::SOLO == running_mode) - std::cout << "XBeeMav Running in SOLO Mode..." << std::endl; - else - std::cout << "XBeeMav Running in SWARM Mode..." << std::endl; + if (RUNNING_MODE::SOLO == running_mode) + std::cout << "XBeeMav Running in SOLO Mode..." << std::endl; + else + std::cout << "XBeeMav Running in SWARM Mode..." << std::endl; } //***************************************************************************** void CommunicationManager::Process_In_Standard_Messages() { - std::size_t in_messages_size = in_std_messages_.Get_Size(); - - if (in_messages_size > 0) - { - for (std::size_t j = 0; j < in_messages_size; j++) - { - std::shared_ptr in_message = - in_std_messages_.Pop_Front(); - mavros_msgs::Mavlink mavlink_msg; - - packets_handler_.Deserialize_Mavlink_Message(in_message->c_str(), &mavlink_msg, in_message->size()); - mavlink_publisher_.publish(mavlink_msg); - } - } + std::size_t in_messages_size = in_std_messages_.Get_Size(); + + if (in_messages_size > 0) + { + for (std::size_t j = 0; j < in_messages_size; j++) + { + std::shared_ptr in_message = + in_std_messages_.Pop_Front(); + mavros_msgs::Mavlink mavlink_msg; + + packets_handler_.Deserialize_Mavlink_Message(in_message->c_str(), &mavlink_msg, in_message->size()); + mavlink_publisher_.publish(mavlink_msg); + } + } } //***************************************************************************** void CommunicationManager::Process_In_Acks_and_Pings() { - std::size_t in_messages_size = in_Acks_and_Pings_.Get_Size(); - - if (in_messages_size > 0) - { - for (std::size_t j = 0; j < in_messages_size; j++) - { - std::shared_ptr in_message = - in_Acks_and_Pings_.Pop_Front(); - - packets_handler_.Process_Ping_Or_Acknowledgement(in_message); - } - } + std::size_t in_messages_size = in_Acks_and_Pings_.Get_Size(); + + if (in_messages_size > 0) + { + for (std::size_t j = 0; j < in_messages_size; j++) + { + std::shared_ptr in_message = + in_Acks_and_Pings_.Pop_Front(); + + packets_handler_.Process_Ping_Or_Acknowledgement(in_message); + } + } } //***************************************************************************** void CommunicationManager::Process_In_Fragments() { - std::size_t in_messages_size = in_fragments_.Get_Size(); - - if (in_messages_size > 0) - { - for (std::size_t j = 0; j < in_messages_size; j++) - { - std::shared_ptr in_message = - in_fragments_.Pop_Front(); - - packets_handler_.Process_Fragment(in_message); - } - } + std::size_t in_messages_size = in_fragments_.Get_Size(); + + if (in_messages_size > 0) + { + for (std::size_t j = 0; j < in_messages_size; j++) + { + std::shared_ptr in_message = + in_fragments_.Pop_Front(); + + packets_handler_.Process_Fragment(in_message); + } + } } - - + + //***************************************************************************** void CommunicationManager::Process_In_Packets() + /* This function publish MAVROS msgs comming the xbee network. + */ { - std::size_t in_messages_size = in_packets_.Get_Size(); - - if (in_messages_size > 0) - { - for (std::size_t j = 0; j < in_messages_size; j++) - { - std::shared_ptr in_message = - in_packets_.Pop_Front(); - mavros_msgs::Mavlink mavlink_msg; - - packets_handler_.Deserialize_Mavlink_Message(in_message->c_str(), &mavlink_msg, in_message->size()); - mavlink_publisher_.publish(mavlink_msg); - } - } + std::size_t in_messages_size = in_packets_.Get_Size(); + + if (in_messages_size > 0) + { + for (std::size_t j = 0; j < in_messages_size; j++) + { + std::shared_ptr in_message = + in_packets_.Pop_Front(); + mavros_msgs::Mavlink mavlink_msg; + + packets_handler_.Deserialize_Mavlink_Message(in_message->c_str(), &mavlink_msg, in_message->size()); + mavlink_publisher_.publish(mavlink_msg); + } + } } //***************************************************************************** void CommunicationManager::Process_Command_Responses() -{ - std::size_t in_messages_size = command_responses_.Get_Size(); - - if (in_messages_size > 0) - { - for (std::size_t j = 0; j < in_messages_size; j++) - { - std::shared_ptr in_message = - command_responses_.Pop_Front(); - - packets_handler_.Process_Command_Response(in_message->c_str()); - } - } + /* This function forwards the command responses to the packethandler to be + * processed. + */ +{ + std::size_t in_messages_size = command_responses_.Get_Size(); + + if (in_messages_size > 0) + { + for (std::size_t j = 0; j < in_messages_size; j++) + { + std::shared_ptr in_message = + command_responses_.Pop_Front(); + + packets_handler_.Process_Command_Response(in_message->c_str()); + } + } } -bool CommunicationManager::Get_Param (mavros_msgs::ParamGet::Request& req, mavros_msgs::ParamGet::Response& res){ -mavros_msgs::ParamValue val; -if(req.param_id=="id"){ - val.integer=packets_handler_.get_device_id(); -} else if(req.param_id=="rssi"){ - val.integer=-1; -} else if(req.param_id=="pl"){ - val.integer=-1; +//***************************************************************************** +bool CommunicationManager::Get_Param (mavros_msgs::ParamGet::Request& req, + mavros_msgs::ParamGet::Response& res) + /* This function processes the requests sent to the xbee_status rosservice + * The response success is set to true if the param_id of the request is known + * Return: true + */ + //TODO these ids need to be defined as constants +{ + mavros_msgs::ParamValue val; + res.success = true; + + if(req.param_id == "id") + { + val.integer=packets_handler_.getDeviceId(); + } + if(req.param_id == "deque_full") + { + val.integer=packets_handler_.getDequeFull(); + } + ///////////////////////////////////////////////////////// + // RSSI Section + else if(req.param_id == "rssi") + { + val.real=packets_handler_.getSignalStrength(); + } + else if(req.param_id == "trig_rssi_api_avg") + { + if(packets_handler_.triggerAPIRssiUpdate(rssi_payload_size_, + rssi_iterations_, + PacketsHandler::ALL_IDS) == 0) + { + res.success = false; + } + } + else if (safeSubStr(req.param_id, 14) == "trig_rssi_api_") + { + int short_id = std::strtol(req.param_id.substr(14).c_str(), NULL, 10); + if(packets_handler_.triggerAPIRssiUpdate(rssi_payload_size_, + rssi_iterations_, + static_cast(short_id)) == 0) + { + res.success = false; + } + } + else if (req.param_id == "get_rssi_api_avg") + { + val.real = packets_handler_.getAPISignalStrength(PacketsHandler::ALL_IDS); + if(val.real == 0){res.success = false;} + } + else if (safeSubStr(req.param_id, 13) == "get_rssi_api_") + { + int short_id = std::strtol(req.param_id.substr(13).c_str(), NULL, 10); + val.integer = short_id; + val.real = packets_handler_.getAPISignalStrength(static_cast(short_id)); + if(val.real == 0){res.success = false;} + } + ///////////////////////////////////////////////////////// + // Packet loss Section + else if (req.param_id == "pl_raw_avg") + { + val.real = packets_handler_.getRawPacketLoss(PacketsHandler::ALL_IDS); + if(val.real == PacketsHandler::PACKET_LOSS_UNAVAILABLE){res.success = false;} + } + else if (safeSubStr(req.param_id, 7) == "pl_raw_") + { + int short_id = std::strtol(req.param_id.substr(7).c_str(), NULL, 10); + val.integer = short_id; + val.real = packets_handler_.getRawPacketLoss(static_cast(short_id)); + if(val.real == PacketsHandler::PACKET_LOSS_UNAVAILABLE){res.success = false;} + } + else if (req.param_id == "pl_filtered_avg") + { + val.real = packets_handler_.getPacketLoss(PacketsHandler::ALL_IDS); + if(val.real == PacketsHandler::PACKET_LOSS_UNAVAILABLE){res.success = false;} + } + else if (safeSubStr(req.param_id, 12) == "pl_filtered_") + { + int short_id = std::strtol(req.param_id.substr(12).c_str(), NULL, 10); + val.integer = short_id; + val.real = packets_handler_.getPacketLoss(static_cast(short_id)); + if(val.real == PacketsHandler::PACKET_LOSS_UNAVAILABLE){res.success = false;} + } + else + { + res.success = false; + } + + res.value = val; + return true; } -res.value= val; -res.success=true; -return true; + +//***************************************************************************** +bool CommunicationManager::getRosParams() +/* This function queries all the ROS parameters. + * Return False if a mandatory parameter could not be queried. + */ +{ + std::string out_messages_topic; + std::string in_messages_topic; + bool success_get_param_in_topic = false; + bool success_get_param_out_topic = false; + + if (node_handle_.getParam("status_service", out_messages_topic)) + { + StatusSrv_ = node_handle_.advertiseService(out_messages_topic.c_str(), + &CommunicationManager::Get_Param, this); + } + else + { + std::cout << "Failed to Get Status Service Name: param 'status_service' Not Found." << std::endl; + } + + if (node_handle_.getParam("Xbee_In_From_Buzz", out_messages_topic)) + { + mavlink_subscriber_ = node_handle_.subscribe(out_messages_topic.c_str(), 100, + &CommunicationManager::Send_Mavlink_Message_Callback, this); + success_get_param_in_topic = true; + } + else + { + std::cout << "Failed to Get Topic Name: param 'Xbee_In_From_Buzz' Not Found." << std::endl; + } + + if (node_handle_.getParam("Xbee_Out_To_Buzz", in_messages_topic)) + { + mavlink_publisher_ = node_handle_.advertise( + in_messages_topic.c_str(), 100); + success_get_param_out_topic = true; + } + else + { + std::cout << "Failed to Get Topic Name: param 'Xbee_Out_To_Buzz' Not Found." << std::endl; + } + + rate_divider_rssi_ = static_cast(getIntParam("rate_divider_rssi", DEFAULT_RSSI_ITERATIONS)); + rate_divider_packet_loss_ = static_cast(getIntParam("rate_divider_packet_loss_", DEFAULT_RSSI_ITERATIONS)); + rssi_payload_size_ = static_cast(getIntParam("rssi_payload_size", DEFAULT_RSSI_ITERATIONS)); + rssi_iterations_ = static_cast(getIntParam("rssi_iterations", DEFAULT_RSSI_ITERATIONS)); + + return success_get_param_in_topic && success_get_param_out_topic; +} + +//***************************************************************************** +int CommunicationManager::getIntParam(std::string name, int default_value) +{ + int temp_param; + if(node_handle_.getParam(name, temp_param)) + { + return temp_param; + } + else + { + return default_value; + } +} + +//***************************************************************************** +void CommunicationManager::triggerRssiUpdate() +{ + /* This trigger the update of the rssi parameter (Signal strength) every + * rate_divider_rssi_ cycles + */ + static uint8_t rssi_update_count = 0; + + rssi_update_count++; + if(rssi_update_count >= rate_divider_rssi_){ + packets_handler_.triggerRssiUpdate(); + rssi_update_count = 0; + } +} + +//***************************************************************************** +void CommunicationManager::Process_Packet_Loss() +{ + /* This function passes the packet loss messages to the packethandler to be + * processed. + * It also sends the packet loss messages to the other every + * rate_divider_packet_loss_ cycles + */ + std::size_t in_messages_size = in_packet_loss_.Get_Size(); + + if (in_messages_size > 0) + { + for (std::size_t j = 0; j < in_messages_size; j++) + { + std::shared_ptr in_message = + in_packet_loss_.Pop_Front(); + + packets_handler_.processPacketLoss(in_message->c_str()); + } + } + + packet_loss_timer_++; + if (packet_loss_timer_ > rate_divider_packet_loss_) + { + packets_handler_.sendPacketLoss(); + packet_loss_timer_ = 0; + } +} + +//***************************************************************************** +std::string CommunicationManager::safeSubStr(const std::string strg, + const unsigned int index_max) const +/* Verify if the operation substr(0, index_max) is possible on the given string + * and return the substring if successful. + * Error value: empty string; + */ +{ + if(strg.size() > index_max) { + return strg.substr(0,index_max); + } + return std::string(""); + } } - } diff --git a/src/PacketsHandler.cpp b/src/PacketsHandler.cpp index f662614..cbc680f 100644 --- a/src/PacketsHandler.cpp +++ b/src/PacketsHandler.cpp @@ -1,9 +1,20 @@ /* PacketsHandler.cpp -- Packets Handler class for XBee: - Serialize, deserialize, fragment and reassemly mavlink - messages (packets and std messages) -- */ + Serialize, deserialize, fragment and reassemly mavlink + messages (packets and std messages) -- */ /* ------------------------------------------------------------------------- */ /* February 06, 2017 -- @Copyright Aymen Soussia. All rights reserved. */ /* (aymen.soussia@gmail.com) */ +/* Revision + * Date: July 1st, 2017 + * Author: Pierre-Yves Breches + */ +/* ------------------------------------------------------------------------- */ +/* TODO + * * Split PacketsHandler class (the last two could be instantiated by the first one) + * * class PacketsHandler + * * class PacketsLossHandler + * * class APIRssiHandler + */ #include"PacketsHandler.h" @@ -16,19 +27,27 @@ namespace Mist namespace Xbee { +const uint8_t PacketsHandler::ALL_IDS = 0xFF; +const uint16_t PacketsHandler::PACKET_LOSS_UNAVAILABLE = 0xFFFF; +const uint8_t PacketsHandler::MAX_WAITING_OUT_MSG = 10; //***************************************************************************** PacketsHandler::PacketsHandler(): - MAX_PACEKT_SIZE(64000), - XBEE_NETWORK_MTU(250), - FRAGMENT_HEADER_SIZE(6), - MAX_TIME_TO_SEND_PACKET(30000), - START_DLIMITER(static_cast(0x7E)), - device_64_bits_address_("12345678"), - loaded_SL_(false), - loaded_SH_(false), - optimum_MT_NBR_(3), - delay_interframes_(100 * 1000) + MAX_PACEKT_SIZE(64000), + XBEE_NETWORK_MTU(250), + FRAGMENT_HEADER_SIZE(6), + MAX_TIME_TO_SEND_PACKET(30000), // TO DO change it to packet time out + RSSI_COMMAND("DB"), + RSSI_FILTER_GAIN(0.5), + PACKET_LOSS_IDENTIFIER("L"), + MAX_PACKET_LOSS_MSG_ID(100), + PACKET_LOSS_FILTER_GAIN(0.7), + device_64_bits_address_("12345678"), + loaded_SL_(false), + loaded_SH_(false), + rssi_float_(0), + optimum_MT_NBR_(3), + delay_interframes_(100 * 1000) { } @@ -41,425 +60,493 @@ PacketsHandler::~PacketsHandler() //***************************************************************************** bool PacketsHandler::Init(SerialDevice* serial_device, - Thread_Safe_Deque* in_packets) + Thread_Safe_Deque* in_packets) { - serial_device_ = serial_device; - - if (!Load_Database_Addresses()) - return false; - - Send_SL_and_SH_Commands(); - in_packets_ = in_packets; - - return true; + serial_device_ = serial_device; + + if (!Load_Database_Addresses()) + return false; + + // TO DO node dicov + + Send_SL_and_SH_Commands(); + in_packets_ = in_packets; + + return true; } //***************************************************************************** bool PacketsHandler::Init_Device_ID() { - if (Get_Local_Address()) - return true; - else - return false; + if (Get_Local_Address()) + return true; + else + return false; } //***************************************************************************** void PacketsHandler::Run() -{ - quit_.store(false); - - while (!quit_.load()) - { - Process_Out_Standard_Messages(); - Process_Out_Packets(); - } +{ + quit_.store(false); + + while (!quit_.load()) + { + Process_Out_Standard_Messages(); + Process_Out_Packets(); + } } //***************************************************************************** void PacketsHandler::Handle_Mavlink_Message(const mavros_msgs::Mavlink::ConstPtr& mavlink_msg) { - std::shared_ptr serialized_packet = - std::make_shared(); - - Serialize_Mavlink_Message(mavlink_msg, serialized_packet); - - if (serialized_packet->size() > XBEE_NETWORK_MTU && serialized_packet->size() <= MAX_PACEKT_SIZE) - { - std::shared_ptr>> fragmented_packet = - std::make_shared>>(); - - std::size_t offset = 0; - std::size_t NBR_of_bytes = 0; - std::size_t NBR_of_fragments = std::ceil( - static_cast(serialized_packet->size()) / XBEE_NETWORK_MTU); - - for (uint8_t i = 0; i < NBR_of_fragments; i++) - { - fragmented_packet->push_back(std::make_shared()); - NBR_of_bytes = std::min(XBEE_NETWORK_MTU, serialized_packet->size() - offset); - Insert_Fragment_Header(false, fragmented_packet->at(i), mavlink_msg->msgid, i, offset); - fragmented_packet->at(i)->append(serialized_packet->c_str() + offset, NBR_of_bytes); - offset += NBR_of_bytes; - } - - out_packets_.Push_Back({mavlink_msg->msgid, fragmented_packet}); - } - else if (serialized_packet->size() < XBEE_NETWORK_MTU) - { - serialized_packet->insert(0, 1, 'S'); - out_std_messages_.Push_Back(serialized_packet); - } + std::shared_ptr serialized_packet = + std::make_shared(); + + Serialize_Mavlink_Message(mavlink_msg, serialized_packet); + + if (serialized_packet->size() > XBEE_NETWORK_MTU && serialized_packet->size() <= MAX_PACEKT_SIZE) + { + std::shared_ptr>> fragmented_packet = + std::make_shared>>(); + + std::size_t offset = 0; + std::size_t NBR_of_bytes = 0; + std::size_t NBR_of_fragments = std::ceil( + static_cast(serialized_packet->size()) / XBEE_NETWORK_MTU); + + for (uint8_t i = 0; i < NBR_of_fragments; i++) + { + fragmented_packet->push_back(std::make_shared()); + NBR_of_bytes = std::min(XBEE_NETWORK_MTU, serialized_packet->size() - offset); + Insert_Fragment_Header(false, fragmented_packet->at(i), mavlink_msg->msgid, i, offset); + fragmented_packet->at(i)->append(serialized_packet->c_str() + offset, NBR_of_bytes); + offset += NBR_of_bytes; + } + out_packets_.Push_Back({static_cast(mavlink_msg->msgid & 0xFF), + fragmented_packet}); + } + else if (serialized_packet->size() < XBEE_NETWORK_MTU) + { + serialized_packet->insert(0, 1, 'S'); + out_std_messages_.Push_Back(serialized_packet); + } } //***************************************************************************** void PacketsHandler::Process_Fragment(std::shared_ptr fragment) { - uint8_t packet_ID = fragment->at(1); - uint8_t node_8_bits_address = fragment->at(2); - uint8_t fragment_ID = fragment->at(3); - uint16_t offset = static_cast( - static_cast(static_cast(fragment->at(4))) << 8 | - static_cast(static_cast(fragment->at(5)))); - - assembly_map_it_ = packets_assembly_map_.find(node_8_bits_address); - - if (assembly_map_it_ != packets_assembly_map_.end()) - { - if (assembly_map_it_->second.packet_ID_ == packet_ID) - { - std::set::iterator it = assembly_map_it_->second.received_fragments_IDs_.find(fragment_ID); - - if (it == assembly_map_it_->second.received_fragments_IDs_.end()) - { - if (assembly_map_it_->second.received_fragments_IDs_.size() == 0) - assembly_map_it_->second.time_since_creation_ = std::clock(); - - Insert_Fragment_In_Packet_Buffer(&assembly_map_it_->second.packet_buffer_, fragment->c_str(), offset, fragment->size()); - assembly_map_it_->second.received_fragments_IDs_.insert(fragment_ID); - } - } - else - { - assembly_map_it_->second = {}; - assembly_map_it_->second.packet_ID_ = packet_ID; - Insert_Fragment_In_Packet_Buffer(&assembly_map_it_->second.packet_buffer_, fragment->c_str(), offset, fragment->size()); - assembly_map_it_->second.received_fragments_IDs_.insert(fragment_ID); - assembly_map_it_->second.time_since_creation_ = std::clock(); - } - } - else - { - Add_New_Node_To_Network(node_8_bits_address); - assembly_map_it_ = packets_assembly_map_.find(node_8_bits_address); - assembly_map_it_->second.packet_ID_ = packet_ID; - Insert_Fragment_In_Packet_Buffer(&assembly_map_it_->second.packet_buffer_, fragment->c_str(), offset, fragment->size()); - assembly_map_it_->second.received_fragments_IDs_.insert(fragment_ID); - assembly_map_it_->second.time_since_creation_ = std::clock(); - } + uint8_t packet_ID = fragment->at(1); + uint8_t node_8_bits_address = fragment->at(2); + uint8_t fragment_ID = fragment->at(3); + uint16_t offset = static_cast( + static_cast(static_cast(fragment->at(4))) << 8 | + static_cast(static_cast(fragment->at(5)))); + + assembly_map_it_ = packets_assembly_map_.find(node_8_bits_address); + packet_loss_it_ = packet_loss_map_.find(node_8_bits_address); + + if (packet_loss_it_ != packet_loss_map_.end()) + packet_loss_it_->second.received_packets_ = packet_loss_it_->second.received_packets_ + 1; + + if (assembly_map_it_ != packets_assembly_map_.end()) + { + if (assembly_map_it_->second.packet_ID_ == packet_ID) + { + std::set::iterator it = assembly_map_it_->second.received_fragments_IDs_.find(fragment_ID); + + if (it == assembly_map_it_->second.received_fragments_IDs_.end()) + { + if (assembly_map_it_->second.received_fragments_IDs_.size() == 0) + assembly_map_it_->second.time_since_creation_ = std::clock(); + + Insert_Fragment_In_Packet_Buffer(&assembly_map_it_->second.packet_buffer_, fragment->c_str(), offset, fragment->size()); + assembly_map_it_->second.received_fragments_IDs_.insert(fragment_ID); + } + } + else + { + assembly_map_it_->second = {}; + assembly_map_it_->second.packet_ID_ = packet_ID; + Insert_Fragment_In_Packet_Buffer(&assembly_map_it_->second.packet_buffer_, fragment->c_str(), offset, fragment->size()); + assembly_map_it_->second.received_fragments_IDs_.insert(fragment_ID); + assembly_map_it_->second.time_since_creation_ = std::clock(); + } + } + else + { + Add_New_Node_To_Network(node_8_bits_address); + assembly_map_it_ = packets_assembly_map_.find(node_8_bits_address); + assembly_map_it_->second.packet_ID_ = packet_ID; + Insert_Fragment_In_Packet_Buffer(&assembly_map_it_->second.packet_buffer_, fragment->c_str(), offset, fragment->size()); + assembly_map_it_->second.received_fragments_IDs_.insert(fragment_ID); + assembly_map_it_->second.time_since_creation_ = std::clock(); + } } //***************************************************************************** -void PacketsHandler::Insert_Fragment_In_Packet_Buffer(std::string* buffer, const char* fragment, const uint16_t offset, const std::size_t length) +void PacketsHandler::Insert_Fragment_In_Packet_Buffer(std::string* buffer, const char* fragment, const uint16_t offset, const std::size_t length) // TO DO delete length { - if (offset >= buffer->size()) - buffer->append(fragment + FRAGMENT_HEADER_SIZE, length - FRAGMENT_HEADER_SIZE); - else - buffer->insert(offset, fragment + FRAGMENT_HEADER_SIZE, length - FRAGMENT_HEADER_SIZE); + if (offset >= buffer->size()) + buffer->append(fragment + FRAGMENT_HEADER_SIZE, length - FRAGMENT_HEADER_SIZE); + else + buffer->insert(offset, fragment + FRAGMENT_HEADER_SIZE, length - FRAGMENT_HEADER_SIZE); } //***************************************************************************** -void PacketsHandler::Process_Ping_Or_Acknowledgement(std::shared_ptr frame) +void PacketsHandler::Process_Ping_Or_Acknowledgement(std::shared_ptr frame) // TO DO change useless std::shared_ptr frame args to ->c_str() { - uint8_t packet_ID = frame->at(12); - uint8_t node_8_bits_address = frame->at(13); - - if (frame->at(11) == 'A') - { - mutex_.lock(); - - connected_network_nodes_it_ = connected_network_nodes_.find(node_8_bits_address); - - if (connected_network_nodes_it_ == connected_network_nodes_.end()) - { - mutex_.unlock(); - Add_New_Node_To_Network(node_8_bits_address); - mutex_.lock(); - connected_network_nodes_it_ = connected_network_nodes_.find(node_8_bits_address); - } + uint8_t packet_ID = frame->at(12); + uint8_t node_8_bits_address = frame->at(13); - if (packet_ID == current_processed_packet_ID_) - { - if (frame->size() < 15) - connected_network_nodes_it_->second = true; - else - { - for (uint8_t i = 14; i < frame->size(); i++) - fragments_indexes_to_transmit_.insert(frame->at(i)); - } - } - - mutex_.unlock(); - } - else if (frame->at(11) == 'P') - { - assembly_map_it_ = packets_assembly_map_.find(node_8_bits_address); - - if (assembly_map_it_ == packets_assembly_map_.end()) - { - Add_New_Node_To_Network(node_8_bits_address); - assembly_map_it_ = packets_assembly_map_.find(node_8_bits_address); - assembly_map_it_->second.packet_ID_ = packet_ID; - assembly_map_it_->second.time_since_creation_ = std::clock(); - } - - if (assembly_map_it_->second.packet_ID_ == packet_ID) - { - std::string Acknowledgement = "A"; - Acknowledgement.push_back(packet_ID); - Acknowledgement.push_back(device_address_); - uint8_t packet_size = frame->at(14); - - if (assembly_map_it_->second.received_fragments_IDs_.size() == packet_size) - { - in_packets_->Push_Back(std::make_shared(assembly_map_it_->second.packet_buffer_)); - assembly_map_it_->second.packet_buffer_.clear(); - assembly_map_it_->second.received_fragments_IDs_.clear(); - assembly_map_it_->second.time_since_creation_ = 0; - } - else - { - std::set::iterator it = assembly_map_it_->second.received_fragments_IDs_.begin(); - uint8_t j = 0; - - while (j <= packet_size - 1) - { - if (j != *it) - Acknowledgement.push_back(j); - else if (it != std::prev(assembly_map_it_->second.received_fragments_IDs_.end())) - it++; + if (frame->at(11) == 'A') + { + mutex_.lock(); - j++; - } - } - - std::string Ack_frame; - Generate_Transmit_Request_Frame(Acknowledgement.c_str(), &Ack_frame, Acknowledgement.size()); - serial_device_->Send_Frame(Ack_frame); - usleep(delay_interframes_); - - } - else - { - assembly_map_it_->second = {}; - assembly_map_it_->second.packet_ID_ = packet_ID; - } - } + connected_network_nodes_it_ = connected_network_nodes_.find(node_8_bits_address); + + if (connected_network_nodes_it_ == connected_network_nodes_.end()) + { + mutex_.unlock(); + Add_New_Node_To_Network(node_8_bits_address); + mutex_.lock(); + connected_network_nodes_it_ = connected_network_nodes_.find(node_8_bits_address); + } + + if (packet_ID == current_processed_packet_ID_) + { + if (frame->size() < 15) + connected_network_nodes_it_->second = true; + else + { + for (uint8_t i = 14; i < frame->size(); i++) + fragments_indexes_to_transmit_.insert(frame->at(i)); + } + } + + mutex_.unlock(); + } + else if (frame->at(11) == 'P') + { + assembly_map_it_ = packets_assembly_map_.find(node_8_bits_address); + + if (assembly_map_it_ == packets_assembly_map_.end()) + { + Add_New_Node_To_Network(node_8_bits_address); + assembly_map_it_ = packets_assembly_map_.find(node_8_bits_address); + assembly_map_it_->second.packet_ID_ = packet_ID; + assembly_map_it_->second.time_since_creation_ = std::clock(); + } + + if (assembly_map_it_->second.packet_ID_ == packet_ID) + { + std::string Acknowledgement = "A"; + Acknowledgement.push_back(packet_ID); + Acknowledgement.push_back(device_address_); + uint8_t packet_size = frame->at(14); + + if (assembly_map_it_->second.received_fragments_IDs_.size() == packet_size) + { + // TO DO add test if the packet was already transmitted to rosbuzz dont transmit ack only if + in_packets_->Push_Back(std::make_shared(assembly_map_it_->second.packet_buffer_)); + assembly_map_it_->second.packet_buffer_.clear(); + assembly_map_it_->second.received_fragments_IDs_.clear(); + assembly_map_it_->second.time_since_creation_ = 0; + } + else + { + std::set::iterator it = assembly_map_it_->second.received_fragments_IDs_.begin(); + uint8_t j = 0; + + while (j <= packet_size - 1) + { + if (j != *it) + Acknowledgement.push_back(j); + else if (it != std::prev(assembly_map_it_->second.received_fragments_IDs_.end())) + it++; + + j++; + } + } + + std::string Ack_frame; + Generate_Transmit_Request_Frame(Acknowledgement.c_str(), &Ack_frame, Acknowledgement.size()); + serial_device_->Send_Frame(Ack_frame); + usleep(delay_interframes_); + + } + else + { + assembly_map_it_->second = {}; + assembly_map_it_->second.packet_ID_ = packet_ID; + } + } } //***************************************************************************** void PacketsHandler::Add_New_Node_To_Network(const uint8_t new_node_address) { - std::set empty_set; - packets_assembly_map_.insert(std::pair(new_node_address, {})); - - std::lock_guard guard(mutex_); - connected_network_nodes_.insert(std::pair(new_node_address, false)); + std::set empty_set; + packets_assembly_map_.insert(std::pair(new_node_address, {})); + + std::lock_guard guard(mutex_); + connected_network_nodes_.insert(std::pair(new_node_address, false)); } //***************************************************************************** void PacketsHandler::Process_Command_Response(const char* command_response) { - if (command_response[0] == 'N' && command_response[1] == 'D') - { - uint64_t new_node_address = 0; - std::lock_guard guard(mutex_); - - if (command_response[2] == static_cast(0)) - { - new_node_address = static_cast( - static_cast(command_response[5]) << 56 | - static_cast(command_response[6]) << 48 | - static_cast(command_response[7]) << 40 | - static_cast(command_response[8]) << 32 | - static_cast(command_response[9]) << 24 | - static_cast(command_response[10]) << 16 | - static_cast(command_response[11]) << 8 | - static_cast(command_response[12])); - } - - database_addresses_it_ = database_addresses_.find(new_node_address); - - if (database_addresses_it_ != database_addresses_.end()) - device_address_ = database_addresses_it_->second; - else - std::cout << "Remote Node Not in Database" << std::endl; - } - else if (command_response[0] == 'S' && command_response[1] == 'H') - { - if (command_response[2] == static_cast(0)) - { - loaded_SH_ = true; - - for (std::size_t i = 0; i < 4; i++) - device_64_bits_address_[i] = command_response[3 + i]; - } - } - else if (command_response[0] == 'S' && command_response[1] == 'L') - { - if (command_response[2] == static_cast(0)) - { - loaded_SL_ = true; - - for (std::size_t i = 0; i < 4; i++) - device_64_bits_address_[4 + i] = command_response[3 + i]; - } - } + if (command_response[0] == 'N' && command_response[1] == 'D') + { + uint64_t new_node_address = 0; + std::lock_guard guard(mutex_); + + if (command_response[2] == static_cast(0)) // TO DO check this + { + new_node_address = get64BitsAddress(command_response, 5); + } + + database_addresses_it_ = database_addresses_.find(new_node_address); + + if (database_addresses_it_ != database_addresses_.end()) + device_address_ = database_addresses_it_->second; + else + std::cout << "Remote Node Not in Database" << std::endl; + } + else if (command_response[0] == 'S' && command_response[1] == 'H') + { + if (command_response[2] == static_cast(0)) + { + loaded_SH_ = true; + + for (std::size_t i = 0; i < 4; i++) + device_64_bits_address_[i] = command_response[3 + i]; + } + } + else if (command_response[0] == 'S' && command_response[1] == 'L') + { + if (command_response[2] == static_cast(0)) + { + loaded_SL_ = true; + + for (std::size_t i = 0; i < 4; i++) + device_64_bits_address_[4 + i] = command_response[3 + i]; + } + } + else if (command_response[0] == 'D' && command_response[1] == 'B') + { + // TODO implemetation of a handler for error value responses (outside valid range) + rssi_float_ = filterIIR(static_cast(static_cast(command_response[3])), + rssi_float_, + RSSI_FILTER_GAIN); + } + else if (command_response[0] == 'R' && command_response[1] == 'S') + { + processAPIRssi(command_response); + } + else + { + // nothing to do + } } +//***************************************************************************** +void PacketsHandler::processAPIRssi(const char* command_response) +{ + uint64_t node_address = get64BitsAddress(command_response, 2); + + database_addresses_it_ = database_addresses_.find(node_address); + if (database_addresses_it_ != database_addresses_.end()) + { + rssi_result_map_it_ = rssi_result_map_.find(database_addresses_it_->second); + if(rssi_result_map_it_ == rssi_result_map_.end()) + { + RSSI_Result result ={ucharToUint16(command_response[10], command_response[11]), + ucharToUint16(command_response[12], command_response[13]), + ucharToUint16(command_response[14], command_response[15]), + ucharToUint16(command_response[16], command_response[17]), + static_cast(command_response[18]), + static_cast(command_response[19]), + static_cast(command_response[20]), + static_cast(command_response[21]), + static_cast(command_response[22]), + NEW_VALUE + }; + rssi_result_map_[database_addresses_it_->second] = result; + } + else + { + rssi_result_map_it_->second.payload_size = ucharToUint16(command_response[10], command_response[11]); + rssi_result_map_it_->second.iterations = ucharToUint16(command_response[12], command_response[13]); + rssi_result_map_it_->second.success = ucharToUint16(command_response[14], command_response[15]); + rssi_result_map_it_->second.retries = ucharToUint16(command_response[16], command_response[17]); + rssi_result_map_it_->second.result = static_cast(command_response[18]); + rssi_result_map_it_->second.rr = static_cast(command_response[19]); + rssi_result_map_it_->second.max_rssi = static_cast(command_response[20]); + rssi_result_map_it_->second.min_rssi = static_cast(command_response[21]); + rssi_result_map_it_->second.avg_rssi = static_cast(command_response[22]); + rssi_result_map_it_->second.status = NEW_VALUE; + } + + } +} //***************************************************************************** void PacketsHandler::Quit() { - quit_.store(true); + quit_.store(true); } //***************************************************************************** void PacketsHandler::Serialize_Mavlink_Message(const mavros_msgs::Mavlink::ConstPtr& - mavlink_msg, std::shared_ptr serialized_packet) + mavlink_msg, std::shared_ptr serialized_packet) { - serialized_packet->push_back(mavlink_msg->sysid); - serialized_packet->push_back(mavlink_msg->msgid); - - std::string bytes="12345678"; - - for (std::size_t j = 0; j < mavlink_msg->payload64.size(); j++) - { - for (std::size_t i = 0; i < 8; i++) - bytes[7 - i] = (mavlink_msg->payload64.at(j) >> (i * 8)); - - serialized_packet->append(bytes); - } + serialized_packet->push_back(mavlink_msg->sysid); + serialized_packet->push_back(mavlink_msg->msgid); + + std::string bytes="12345678"; + + for (std::size_t j = 0; j < mavlink_msg->payload64.size(); j++) + { + for (std::size_t i = 0; i < 8; i++) + bytes[7 - i] = (mavlink_msg->payload64.at(j) >> (i * 8)); + + serialized_packet->append(bytes); + } } //***************************************************************************** void PacketsHandler::Insert_Fragment_Header(bool single_fragment, - std::shared_ptr fragment, const uint8_t packet_ID, - const uint8_t fragment_ID, const uint16_t offset) -{ - if (!single_fragment) - { - fragment->push_back('F'); - fragment->push_back(packet_ID); - fragment->push_back(device_address_); - fragment->push_back(fragment_ID); - fragment->push_back(offset >> (1 * 8)); - fragment->push_back(offset >> (0 * 8)); - } - else - fragment->push_back('S'); + std::shared_ptr fragment, const uint8_t packet_ID, + const uint8_t fragment_ID, const uint16_t offset) // TO DO change this function +{ + if (!single_fragment) // TO DO delete + { + fragment->push_back('F'); + fragment->push_back(packet_ID); + fragment->push_back(device_address_); + fragment->push_back(fragment_ID); + fragment->push_back(offset >> (1 * 8)); + fragment->push_back(offset >> (0 * 8)); + } + else // TO DO delete + fragment->push_back('S'); // TO DO delete } //***************************************************************************** void PacketsHandler::Delete_Packets_With_Time_Out() -{ - for(auto& iterator: packets_assembly_map_) - { - if (std::clock_t() - iterator.second.time_since_creation_ > MAX_TIME_TO_SEND_PACKET && iterator.second.time_since_creation_ != 0) - iterator.second = {}; - } +{ + for(auto& iterator: packets_assembly_map_) + { + if (std::clock_t() - iterator.second.time_since_creation_ > MAX_TIME_TO_SEND_PACKET && iterator.second.time_since_creation_ != 0) + iterator.second = {}; + } } //***************************************************************************** void PacketsHandler::Process_Out_Standard_Messages() { - std::size_t deque_size = out_std_messages_.Get_Size(); - - if (deque_size > 0) - { - std::string frame; - std::shared_ptr out_message; - - for (std::size_t i = 0; i < deque_size; i++) - { - frame.clear(); - out_message = out_std_messages_.Pop_Front(); - - Generate_Transmit_Request_Frame(out_message->c_str(), &frame, out_message->size()); - serial_device_->Send_Frame(frame); - usleep(delay_interframes_); - } - } + std::size_t deque_size = out_std_messages_.Get_Size(); + + if (deque_size > 0) + { + std::string frame; + std::shared_ptr out_message; + if(deque_size > MAX_WAITING_OUT_MSG){deque_full_ = true;} + else{deque_full_ = false;} + + + for (std::size_t i = 0; i < deque_size; i++) + { + frame.clear(); + out_message = out_std_messages_.Pop_Front(); + + Generate_Transmit_Request_Frame(out_message->c_str(), &frame, out_message->size()); + serial_device_->Send_Frame(frame); + + for (auto& it:packet_loss_map_) + { + it.second.sent_packets_ = it.second.sent_packets_ + 1; + } + + usleep(delay_interframes_); + } + } } //***************************************************************************** void PacketsHandler::Process_Out_Packets() { - std::size_t deque_size = out_packets_.Get_Size(); - - if (deque_size > 0) - { - Out_Packet_S out_packet; - - for (std::size_t i = 0; i < deque_size; i++) - { - Process_Out_Standard_Messages(); - out_packet = out_packets_.Pop_Front(); + std::size_t deque_size = out_packets_.Get_Size(); - Send_Packet(out_packet); - } - } + if (deque_size > 0) + { + Out_Packet_S out_packet; + + for (std::size_t i = 0; i < deque_size; i++) + { + Process_Out_Standard_Messages(); + out_packet = out_packets_.Pop_Front(); + + Send_Packet(out_packet); + } + } } //***************************************************************************** void PacketsHandler::Send_Packet(const Out_Packet_S& packet) { - std::size_t NBR_of_transmission = 0; - std::vector frames; - - Init_Network_Nodes_For_New_Transmission(packet.packet_ID_, &frames, packet.packet_buffer_); - current_processed_packet_ID_ = packet.packet_ID_; - - std::clock_t start_time = std::clock(); - - while (std::clock() - start_time <= MAX_TIME_TO_SEND_PACKET && !Check_Packet_Transmitted_To_All_Nodes()) - { - NBR_of_transmission++; - Transmit_Fragments(frames); - Send_End_Of_Packet_Ping(packet.packet_ID_, packet.packet_buffer_->size()); - usleep(500 * 1000); - } - - Adjust_Optimum_MT_Number(std::clock() - start_time, NBR_of_transmission); + std::size_t NBR_of_transmission = 0; + std::vector frames; + + Init_Network_Nodes_For_New_Transmission(packet.packet_ID_, &frames, packet.packet_buffer_); + current_processed_packet_ID_ = packet.packet_ID_; + + std::clock_t start_time = std::clock(); + + while (std::clock() - start_time <= MAX_TIME_TO_SEND_PACKET && !Check_Packet_Transmitted_To_All_Nodes()) + { + NBR_of_transmission++; + + Transmit_Fragments(frames); + + // TO DO usleep(flow_control_time) + // TO DO clear fragments_IDs_to_transmit_set + Send_End_Of_Packet_Ping(packet.packet_ID_, packet.packet_buffer_->size()); + usleep(500 * 1000); + // TO DO sleep after ping + } + + Adjust_Optimum_MT_Number(std::clock() - start_time, NBR_of_transmission); } //***************************************************************************** void PacketsHandler::Send_End_Of_Packet_Ping(const uint8_t packet_ID, const uint8_t total_NBR_of_fragments) { - std::string ping_message = "P"; - std::string ping_frame; - - ping_message.push_back(packet_ID); - ping_message.push_back(device_address_); - ping_message.push_back(total_NBR_of_fragments); - - Generate_Transmit_Request_Frame(ping_message.c_str(), &ping_frame, ping_message.size()); - serial_device_->Send_Frame(ping_frame); - usleep(delay_interframes_); + std::string ping_message = "P"; + std::string ping_frame; + + ping_message.push_back(packet_ID); + ping_message.push_back(device_address_); + ping_message.push_back(total_NBR_of_fragments); + + Generate_Transmit_Request_Frame(ping_message.c_str(), &ping_frame, ping_message.size()); + serial_device_->Send_Frame(ping_frame); + usleep(delay_interframes_); } @@ -511,264 +598,502 @@ bool PacketsHandler::Load_Database_Addresses() //***************************************************************************** bool PacketsHandler::Get_Local_Address() { - const useconds_t ONE_SECOND = 1*1000*1000; /* 1s = 1 * 10⁶ microseconds. */ - usleep(ONE_SECOND); - - if (loaded_SH_ && loaded_SL_) - { - uint64_t local_64_bits_address = ( - static_cast(static_cast(device_64_bits_address_[0])) << 56 | - static_cast(static_cast(device_64_bits_address_[1])) << 48 | - static_cast(static_cast(device_64_bits_address_[2])) << 40 | - static_cast(static_cast(device_64_bits_address_[3])) << 32 | - static_cast(static_cast(device_64_bits_address_[4])) << 24 | - static_cast(static_cast(device_64_bits_address_[5])) << 16 | - static_cast(static_cast(device_64_bits_address_[6])) << 8 | - static_cast(static_cast(device_64_bits_address_[7]))); - - database_addresses_it_ = database_addresses_.find(local_64_bits_address); - - if (database_addresses_it_ != database_addresses_.end()) - { - device_address_ = database_addresses_it_->second; - std::cout << "Loaded Short Device Address : " << static_cast(device_address_) << std::endl; - return true; - } - else - { - std::cout << "Local Address Not Found In Database. Please Add The Xbee Address to database.xml." << std::endl; - return false; - } - } - else - { - Send_SL_and_SH_Commands(); - return false; - } + const useconds_t ONE_SECOND = 1*1000*1000; /* 1s = 1 * 10⁶ microseconds. */ + usleep(ONE_SECOND); + + if (loaded_SH_ && loaded_SL_) + { + uint64_t local_64_bits_address = ( + static_cast(static_cast(device_64_bits_address_[0])) << 56 | + static_cast(static_cast(device_64_bits_address_[1])) << 48 | + static_cast(static_cast(device_64_bits_address_[2])) << 40 | + static_cast(static_cast(device_64_bits_address_[3])) << 32 | + static_cast(static_cast(device_64_bits_address_[4])) << 24 | + static_cast(static_cast(device_64_bits_address_[5])) << 16 | + static_cast(static_cast(device_64_bits_address_[6])) << 8 | + static_cast(static_cast(device_64_bits_address_[7]))); + + database_addresses_it_ = database_addresses_.find(local_64_bits_address); + + if (database_addresses_it_ != database_addresses_.end()) + { + device_address_ = database_addresses_it_->second; + local_64_bits_address_ = local_64_bits_address; + std::cout << "Loaded Short Device Address : " << static_cast(device_address_) << std::endl; + return true; + } + else + { + std::cout << "Local Address Not Found In Database. Please Add The Xbee Address to database.xml." << std::endl; + return false; + } + } + else + { + Send_SL_and_SH_Commands(); + return false; + } } //***************************************************************************** bool PacketsHandler::Check_Packet_Transmitted_To_All_Nodes() { - std::lock_guard guard(mutex_); - - if (connected_network_nodes_.size() == 0) - return false; - - for (auto it : connected_network_nodes_) - { - if (!it.second) - return false; - } - - return true; + std::lock_guard guard(mutex_); + + if (connected_network_nodes_.size() == 0) + return false; + + for (auto it : connected_network_nodes_) + { + if (!it.second) + return false; + } + + return true; } //***************************************************************************** -void PacketsHandler::Init_Network_Nodes_For_New_Transmission(const uint8_t packet_ID, std::vector* frames, std::shared_ptr>> packet) +void PacketsHandler::Init_Network_Nodes_For_New_Transmission(const uint8_t packet_ID, + std::vector* frames, + std::shared_ptr>> packet) { - std::lock_guard guard(mutex_); - fragments_indexes_to_transmit_.clear(); - - for (auto& it : connected_network_nodes_) - it.second = false; - - current_processed_packet_ID_ = packet_ID; - - for (uint8_t i = 0; i < packet->size(); i++) - { - frames->push_back(""); - fragments_indexes_to_transmit_.insert(i); - Generate_Transmit_Request_Frame(packet->at(i)->c_str(), &frames->at(i), packet->at(i)->size()); - } + std::lock_guard guard(mutex_); + fragments_indexes_to_transmit_.clear(); + + for (auto& it : connected_network_nodes_) + it.second = false; + + current_processed_packet_ID_ = packet_ID; + + for (uint8_t i = 0; i < packet->size(); i++) + { + frames->push_back(""); + fragments_indexes_to_transmit_.insert(i); + Generate_Transmit_Request_Frame(packet->at(i)->c_str(), &frames->at(i), packet->at(i)->size()); + } } //***************************************************************************** void PacketsHandler::Transmit_Fragments(const std::vector& frames) { - std::lock_guard guard(mutex_); - - for (auto index: fragments_indexes_to_transmit_) - { - serial_device_->Send_Frame(frames.at(index)); - usleep(delay_interframes_); - } - - fragments_indexes_to_transmit_.clear(); + std::lock_guard guard(mutex_); + + for (auto index: fragments_indexes_to_transmit_) + { + serial_device_->Send_Frame(frames.at(index)); + for (auto& it:packet_loss_map_) + { + it.second.sent_packets_ = it.second.sent_packets_ + 1; + } + + usleep(delay_interframes_); + } + + fragments_indexes_to_transmit_.clear(); } - + //***************************************************************************** void PacketsHandler::Adjust_Optimum_MT_Number(const std::clock_t elapsed_time, - const std::size_t NBR_of_transmission) -{ - if (NBR_of_transmission > 1 && elapsed_time < MAX_TIME_TO_SEND_PACKET) - delay_interframes_ += 5000; - else if (NBR_of_transmission == 1 && delay_interframes_ >= 5000) - delay_interframes_ -= 5000; + const std::size_t NBR_of_transmission) +{ + if (NBR_of_transmission > 1 && elapsed_time < MAX_TIME_TO_SEND_PACKET) + delay_interframes_ += 5000; + else if (NBR_of_transmission == 1 && delay_interframes_ >= 5000) + delay_interframes_ -= 5000; } //***************************************************************************** void PacketsHandler::Send_SL_and_SH_Commands() { - std::string command; - std::string frame; - - command = "SL"; - Generate_AT_Command(command.c_str(), &frame); - serial_device_->Send_Frame(frame); - - command = "SH"; - frame = ""; - Generate_AT_Command(command.c_str(), &frame); - serial_device_->Send_Frame(frame); + std::string command; + std::string frame; + + command = "SL"; + Generate_AT_Command(command.c_str(), &frame); + serial_device_->Send_Frame(frame); + + command = "SH"; + frame = ""; + Generate_AT_Command(command.c_str(), &frame); + serial_device_->Send_Frame(frame); } //***************************************************************************** void PacketsHandler::Deserialize_Mavlink_Message(const char * bytes, - mavros_msgs::Mavlink* mavlink_msg, const std::size_t msg_size) + mavros_msgs::Mavlink* mavlink_msg, const std::size_t msg_size) { - mavlink_msg->sysid = bytes[0]; - mavlink_msg->msgid = bytes[1]; - uint64_t current_int64 = 0; - - for (std::size_t i = 2; i < msg_size; i += 8) - { - current_int64 = ( - static_cast(static_cast(bytes[i])) << 56 | - static_cast(static_cast(bytes[i + 1])) << 48 | - static_cast(static_cast(bytes[i + 2])) << 40 | - static_cast(static_cast(bytes[i + 3])) << 32 | - static_cast(static_cast(bytes[i + 4])) << 24 | - static_cast(static_cast(bytes[i + 5])) << 16 | - static_cast(static_cast(bytes[i + 6])) << 8 | - static_cast(static_cast(bytes[i + 7]))); - - mavlink_msg->payload64.push_back(current_int64); - } -} + mavlink_msg->sysid = bytes[0]; + mavlink_msg->msgid = bytes[1]; + uint64_t current_int64 = 0; + for (std::size_t i = 2; i < msg_size; i += 8) + { + current_int64 = get64BitsAddress(bytes, i); + + mavlink_msg->payload64.push_back(current_int64); + } + + packet_loss_it_ = packet_loss_map_.find(mavlink_msg->sysid); + + if (packet_loss_it_ != packet_loss_map_.end()) + { + packet_loss_it_->second.received_packets_ = packet_loss_it_->second.received_packets_ + 1; + } + else + { + database_addresses_inv_it_ = database_addresses_inv_.find(mavlink_msg->sysid); + if (database_addresses_inv_it_ != database_addresses_inv_.end()) + { + uint64_t long_address = database_addresses_inv_it_->second; + packet_loss_map_.insert(std::pair(mavlink_msg->sysid, + {long_address, 0.0, 0.0, 0, 0, 0, 0})); + } + } +} //***************************************************************************** -inline void PacketsHandler::Generate_Transmit_Request_Frame( - const char* message, - std::string * frame, - const std::size_t message_size, - const unsigned char frame_ID, - const std::string& destination_adssress, - const std::string& short_destination_adress, - const std::string& broadcast_radius, - const std::string& options) -{ - const unsigned char FAME_TYPE = static_cast(0x10); /* Transmit Request Frame */ - std::string frame_parameters; - std::string bytes_frame_parameters; - - frame_parameters.append(destination_adssress); - frame_parameters.append(short_destination_adress); - frame_parameters.append(broadcast_radius); - frame_parameters.append(options); - - Convert_HEX_To_Bytes(frame_parameters, &bytes_frame_parameters); - - frame->push_back(FAME_TYPE); - frame->push_back(frame_ID); - frame->append(bytes_frame_parameters); - frame->append(message, message_size); - - Calculate_and_Append_Checksum(frame); - Add_Length_and_Start_Delimiter(frame); +uint8_t PacketsHandler::getDeviceId(){ + return device_address_; } - //***************************************************************************** -inline void PacketsHandler::Add_Length_and_Start_Delimiter( - std::string* frame) -{ - const unsigned short FIVE_BYTES = 5; - char temporary_buffer[FIVE_BYTES]; - unsigned char temporary_char; - int Hex_frame_length_1; - int Hex_frame_length_2; - std::string header; - int frame_length = frame->size() - 1; /* frame_length = frame_size - checksum byte */ - - header.push_back(START_DLIMITER); - sprintf(temporary_buffer, "%04X", frame_length); - sscanf(temporary_buffer, "%02X%02X", &Hex_frame_length_1, - &Hex_frame_length_2); - temporary_char = static_cast(Hex_frame_length_1); - header.push_back(temporary_char); - temporary_char = static_cast(Hex_frame_length_2); - header.push_back(temporary_char); - frame->insert(0, header); +uint8_t PacketsHandler::getDequeFull(){ + if(deque_full_) {return 1;} + else {return 0;} } - //***************************************************************************** -inline void PacketsHandler::Calculate_and_Append_Checksum( - std::string* frame) +float PacketsHandler::getSignalStrength() { - unsigned short bytes_sum = 0; - unsigned lowest_8_bits = 0; - unsigned short checksum = 0; - unsigned char checksum_byte; - - for (unsigned short i = 0; i < frame->size(); i++) - bytes_sum += static_cast(frame->at(i)); - - lowest_8_bits = bytes_sum & 0xFF; - checksum = 0xFF - lowest_8_bits; - checksum_byte = static_cast(checksum); - frame->push_back(checksum_byte); + return rssi_float_; } - //***************************************************************************** -inline void PacketsHandler::Convert_HEX_To_Bytes( - const std::string& HEX_data, std::string* converted_data) +float PacketsHandler::getAPISignalStrength(uint8_t short_node_id) { - const unsigned short TWO_BYTES = 2; - char temporary_buffer[TWO_BYTES]; - unsigned char temporary_char; - int temporary_HEX; - - for (unsigned short i = 0; i <= HEX_data.size() - TWO_BYTES; - i += TWO_BYTES) - { - memcpy(temporary_buffer, HEX_data.c_str() + i, TWO_BYTES); - sscanf(temporary_buffer, "%02X", &temporary_HEX); - temporary_char = static_cast(temporary_HEX); - converted_data->push_back(temporary_char); - } + float result = 0; + int nb_node = 0; + if(short_node_id == ALL_IDS) + { + for (auto& it:rssi_result_map_) + { + if(it.second.status == NEW_VALUE && + it.second.result == 0x00) + { + nb_node++; + result += static_cast(it.second.avg_rssi); + it.second.status = OLD_VALUE; + } + } + if(nb_node != 0) + { + result = static_cast(result / nb_node); + } + } + else + { + rssi_result_map_it_ = rssi_result_map_.find(short_node_id); + if(rssi_result_map_it_ != rssi_result_map_.end()) + { + if(rssi_result_map_it_->second.status == NEW_VALUE && + rssi_result_map_it_->second.result == 0x00) + { + result = static_cast(rssi_result_map_it_->second.avg_rssi); + rssi_result_map_it_->second.status = OLD_VALUE; + } + } + } + return result; } - //***************************************************************************** -void PacketsHandler::Generate_AT_Command(const char* command, - std::string* frame, - const unsigned char frame_ID) +float PacketsHandler::getRawPacketLoss(uint8_t short_node_id) { - const unsigned char FAME_TYPE = static_cast(0x09);/* AT Command Frame */ - std::string temporary_parameter_value; + if(short_node_id == ALL_IDS) + { + int count = 0; + float result = 0; + for(const auto& it:packet_loss_map_) + { + result += it.second.packet_loss_raw_; + count++; + } + if(count != 0) + { + return result / static_cast(count); + } + else {return PACKET_LOSS_UNAVAILABLE;} + } + else + { + packet_loss_it_ = packet_loss_map_.find(short_node_id); - frame->push_back(FAME_TYPE); - frame->push_back(frame_ID); - frame->append(command); - - Calculate_and_Append_Checksum(frame); - Add_Length_and_Start_Delimiter(frame); + if (packet_loss_it_ != packet_loss_map_.end()) + { + return packet_loss_map_[short_node_id].packet_loss_raw_; + } + else {return PACKET_LOSS_UNAVAILABLE;} + } } -uint8_t PacketsHandler::get_device_id(){ -return device_address_; +//***************************************************************************** +float PacketsHandler::getPacketLoss(uint8_t short_node_id) +{ + if(short_node_id == ALL_IDS) + { + int count = 0; + float result = 0; + for(const auto& it:packet_loss_map_) + { + result += it.second.packet_loss_filtered_; + count++; + } + if(count != 0) + { + return result / static_cast(count); + } + else {return PACKET_LOSS_UNAVAILABLE;} + } + else + { + packet_loss_it_ = packet_loss_map_.find(short_node_id); + + if (packet_loss_it_ != packet_loss_map_.end()) + { + return packet_loss_map_[short_node_id].packet_loss_filtered_; + } + else {return PACKET_LOSS_UNAVAILABLE;} + } } +//***************************************************************************** +void PacketsHandler::triggerRssiUpdate() +/* Description: function sending the AT commad DB to the Xbee module. + * + ------------------------------------------------------------------ */ +{ + std::string frame; + Generate_AT_Command(RSSI_COMMAND.c_str(), &frame); + serial_device_->Send_Frame(frame); +} + +//***************************************************************************** +uint8_t PacketsHandler::triggerAPIRssiUpdate(uint16_t rssi_payload_size, + uint16_t rssi_iterations, + uint8_t target_id) +/* Description: Function triggering the link testing function described + * pages 29-30 in Ressources/XbeeModule_Datasheet.pdf + * The packet_loss_map_ is used to know which nodes are connected + * instead of the connected_network_nodes_ since the latest is only + * updated when a Ping is sent. + ------------------------------------------------------------------ */ +{ + uint8_t sent_request = 0; + + if(target_id == ALL_IDS) + { + for (const auto& it:packet_loss_map_) + { + std::string frame; + generateLinkTestingFrame(&frame, rssi_payload_size, + rssi_iterations, + device_64_bits_address_, + database_addresses_inv_[it.first]); + serial_device_->Send_Frame(frame); + sent_request++; + + rssi_result_map_it_ = rssi_result_map_.find(it.first); + if(rssi_result_map_it_ == rssi_result_map_.end()) + { + RSSI_Result result ={rssi_payload_size, rssi_iterations, 0, 0, 0, + 0, 0, 0, 0, TRIGGERED}; + rssi_result_map_[database_addresses_it_->second] = result; + } + else + { + rssi_result_map_it_->second.payload_size = rssi_payload_size; + rssi_result_map_it_->second.iterations = rssi_iterations; + rssi_result_map_it_->second.avg_rssi = TRIGGERED; + } + + } + } + else + { + packet_loss_it_ = packet_loss_map_.find(target_id); + if(packet_loss_it_ != packet_loss_map_.end()) + { + std::string frame; + generateLinkTestingFrame(&frame, rssi_payload_size, + rssi_iterations, + device_64_bits_address_, + database_addresses_inv_[packet_loss_it_->first]); + serial_device_->Send_Frame(frame); + sent_request++; + + rssi_result_map_it_ = rssi_result_map_.find(target_id); + if(rssi_result_map_it_ == rssi_result_map_.end()) + { + RSSI_Result result ={rssi_payload_size, rssi_iterations, 0, 0, 0, + 0, 0, 0, 0, TRIGGERED}; + rssi_result_map_[database_addresses_it_->second] = result; + } + else + { + rssi_result_map_it_->second.payload_size = rssi_payload_size; + rssi_result_map_it_->second.iterations = rssi_iterations; + rssi_result_map_it_->second.avg_rssi = TRIGGERED; + } + } + } + + return sent_request; +} + +//***************************************************************************** +float PacketsHandler::computePercentage(const int16_t numerator, const int16_t denumerator) const +{ + return static_cast((numerator * 100.0) / (denumerator * 1.0)); +} + +//***************************************************************************** +float PacketsHandler::filterIIR(const float new_val, const float old_val, const float gain) const +{ + return (new_val * (1.0 - gain)) + (old_val * gain); +} + +//***************************************************************************** +void PacketsHandler::processPacketLoss(const char* packet_loss) +{ + uint8_t source_ID = static_cast(packet_loss[1]); + uint16_t received_packet_from_me = static_cast( + static_cast(static_cast(packet_loss[2])) << 8 | + static_cast(static_cast(packet_loss[3]))); + uint8_t packet_loss_msg_id = static_cast(packet_loss[4]); + + packet_loss_it_ = packet_loss_map_.find(source_ID); + + if (packet_loss_it_ != packet_loss_map_.end()) + { + if (packet_loss_msg_id == packet_loss_it_->second.packet_loss_received_id_) + { + packet_loss_it_->second.packet_loss_received_id_ = (packet_loss_it_->second.packet_loss_received_id_ + 1) % MAX_PACKET_LOSS_MSG_ID; + updatePacketLoss(packet_loss_it_->second, received_packet_from_me); + } + else + { + // Missed a packet(s) loss msg, thus we resynchronize the id + packet_loss_it_->second.packet_loss_received_id_ = (packet_loss_msg_id + 1) % MAX_PACKET_LOSS_MSG_ID; + printf("Resynchronized %i\n", packet_loss_it_->second.packet_loss_received_id_); + } + } + else + { + database_addresses_inv_it_ = database_addresses_inv_.find(source_ID); + if (database_addresses_inv_it_ != database_addresses_inv_.end()) + { + uint64_t long_address = database_addresses_inv_it_->second; + packet_loss_map_.insert(std::pair(source_ID, + {long_address, 0.0, 0.0, 0, 0, 0, 0})); + } + } +} + +//***************************************************************************** +void PacketsHandler::updatePacketLoss(On_Line_Node_S& node, const uint16_t received_packet) +/* Description: Update the packet loss of the node: node. + * The information received is condered valid only if: + * - The number of sent packets is different from 0 + * - The number of received packets is inferior to sent_packets + 2 + * + * The + 2 allows the system to take into consideration the messages sent after + * the packet loss information messages was sent. + ------------------------------------------------------------------ */ +{ + if(node.sent_packets_ != 0) // Division by 0 + { + if(node.sent_packets_ + 2 >= received_packet) + { + node.packet_loss_raw_ = computePercentage((static_cast(node.sent_packets_) - static_cast(received_packet)), + node.sent_packets_); + node.packet_loss_filtered_ = filterIIR(node.packet_loss_raw_, + node.packet_loss_filtered_, + PACKET_LOSS_FILTER_GAIN); + } + else + { + printf("Impossible received packet number: %i for %i sent (coming from %lu)", + static_cast(received_packet), + static_cast(node.sent_packets_), + static_cast(node.device_64_bits_address_)); + } + node.sent_packets_ = 0; + + } + else + { + // Do nothing + } +} + +//***************************************************************************** +void PacketsHandler::sendPacketLoss() +{ + for (auto& it:packet_loss_map_) + { + std::string packet_loss_message = PACKET_LOSS_IDENTIFIER; + std::string packet_loss_frame; + + packet_loss_message.push_back(device_address_); + packet_loss_message.push_back((it.second.received_packets_ & 0xFF00) >> 8); + packet_loss_message.push_back(it.second.received_packets_ & 0x00FF); + packet_loss_message.push_back(it.second.packet_loss_sent_id_); + + it.second.received_packets_ = 0; + it.second.packet_loss_sent_id_ = (it.second.packet_loss_sent_id_ + 1) % MAX_PACKET_LOSS_MSG_ID; + + // MSG format L source id received packets packet loss msg id + // 1 byte 8 bits 16 bits 8 bits + Generate_Transmit_Request_Frame(packet_loss_message.c_str(), + &packet_loss_frame, + packet_loss_message.size(), + static_cast(0x01), + int_to_hex(it.second.device_64_bits_address_, 16), + int_to_hex(static_cast(it.first), 4)); + + serial_device_->Send_Frame(packet_loss_frame); + + } +} + +uint16_t PacketsHandler::ucharToUint16(unsigned char msb, unsigned char lsb) +/* Description: return the numerical value of the corresponding + * binary number msb lsb + ------------------------------------------------------------------ */ + { + return (static_cast(msb)<<8) + static_cast(lsb); + } + + inline uint64_t PacketsHandler::get64BitsAddress(const char* bytes, + const int offset) + { + return ( + static_cast(static_cast(bytes[offset])) << 56 | + static_cast(static_cast(bytes[offset + 1])) << 48 | + static_cast(static_cast(bytes[offset + 2])) << 40 | + static_cast(static_cast(bytes[offset + 3])) << 32 | + static_cast(static_cast(bytes[offset + 4])) << 24 | + static_cast(static_cast(bytes[offset + 5])) << 16 | + static_cast(static_cast(bytes[offset + 6])) << 8 | + static_cast(static_cast(bytes[offset + 7]))); + } + } diff --git a/src/SerialDevice.cpp b/src/SerialDevice.cpp index 5b00d0e..6f312bc 100644 --- a/src/SerialDevice.cpp +++ b/src/SerialDevice.cpp @@ -18,7 +18,7 @@ namespace Xbee //***************************************************************************** SerialDevice::SerialDevice(): - serial_port_(io_service_) + serial_port_(io_service_) { } @@ -31,256 +31,280 @@ SerialDevice::~SerialDevice() //***************************************************************************** bool SerialDevice::Init( - const std::string & device, const std::size_t baud_rate) + const std::string & device, const std::size_t baud_rate) { - serial_port_.open(device); - - if (serial_port_.is_open()) - { - Set_Port_Options(baud_rate); - Init_Frame_Type_Keys(); - return true; - } - else - { - std::cout << "Port Failed To Open." << std::endl; - return false; - } + serial_port_.open(device); + + if (serial_port_.is_open()) + { + Set_Port_Options(baud_rate); + Init_Frame_Type_Keys(); + return true; + } + else + { + std::cout << "Port Failed To Open." << std::endl; + return false; + } } //***************************************************************************** void SerialDevice::Set_Port_Options(const std::size_t baud_rate) { - serial_port_.set_option(boost::asio::serial_port::baud_rate(baud_rate)); - serial_port_.set_option(boost::asio::serial_port::character_size(8)); - serial_port_.set_option(boost::asio::serial_port::parity( - boost::asio::serial_port::serial_port_base::parity::none)); - serial_port_.set_option(boost::asio::serial_port::stop_bits( - boost::asio::serial_port::serial_port_base::stop_bits::one)); - serial_port_.set_option(boost::asio::serial_port::flow_control( - boost::asio::serial_port::serial_port_base::flow_control::none)); + serial_port_.set_option(boost::asio::serial_port::baud_rate(baud_rate)); + serial_port_.set_option(boost::asio::serial_port::character_size(8)); + serial_port_.set_option(boost::asio::serial_port::parity( + boost::asio::serial_port::serial_port_base::parity::none)); + serial_port_.set_option(boost::asio::serial_port::stop_bits( + boost::asio::serial_port::serial_port_base::stop_bits::one)); + serial_port_.set_option(boost::asio::serial_port::flow_control( + boost::asio::serial_port::serial_port_base::flow_control::none)); } //***************************************************************************** void SerialDevice::Send_Frame(const std::string& frame) { - io_service_.post( - [this, frame]() - { - bool write_in_progress = !out_messages_.empty(); - out_messages_.push_back(frame); - - if (!write_in_progress) - Write_Frame(); - }); + io_service_.post( + [this, frame]() + { + bool write_in_progress = !out_messages_.empty(); + out_messages_.push_back(frame); + + if (!write_in_progress) + Write_Frame(); + }); } //***************************************************************************** void SerialDevice::Run_Service() { - Read_Frame_Header(); - io_service_.run(); + Read_Frame_Header(); + io_service_.run(); } //***************************************************************************** void SerialDevice::Stop_Service() { - io_service_.post([this]() {io_service_.stop(); }); + io_service_.post([this]() {io_service_.stop(); }); } //***************************************************************************** void SerialDevice::Close_Serial_Port() { - io_service_.post([this]() {serial_port_.close(); }); + io_service_.post([this]() {serial_port_.close(); }); } //***************************************************************************** void SerialDevice::Set_In_Messages_Pointers(Thread_Safe_Deque* in_std_messages, - Thread_Safe_Deque* in_fragments, - Thread_Safe_Deque* in_Acks_and_Pings, - Thread_Safe_Deque* command_responses) + Thread_Safe_Deque* in_fragments, + Thread_Safe_Deque* in_Acks_and_Pings, + Thread_Safe_Deque* command_responses, + Thread_Safe_Deque* in_packet_loss) { - in_std_messages_ = in_std_messages; - in_fragments_ = in_fragments; - in_Acks_and_Pings_ = in_Acks_and_Pings; - command_responses_ = command_responses; + in_std_messages_ = in_std_messages; + in_fragments_ = in_fragments; + in_Acks_and_Pings_ = in_Acks_and_Pings; + command_responses_ = command_responses; + in_packet_loss_ = in_packet_loss; } //***************************************************************************** void SerialDevice::Init_Frame_Type_Keys() { - sscanf("08", "%02X", &FRAME_TYPE_KEYS[AT_COMMAND]); - sscanf("09", "%02X", &FRAME_TYPE_KEYS[AT_COMMAND_QUEUE_REGISTER_VALUE]); - sscanf("10", "%02X", &FRAME_TYPE_KEYS[TRANSMIT_REQUEST]); - sscanf("11", "%02X", - &FRAME_TYPE_KEYS[EXPLICIT_ADDRESSING_COMMAND_FRAME]); - sscanf("17", "%02X", &FRAME_TYPE_KEYS[REMOTE_AT_COMMAND]); - sscanf("88", "%02X", &FRAME_TYPE_KEYS[AT_COMMAND_RESPONSE]); - sscanf("8A", "%02X", &FRAME_TYPE_KEYS[MODEM_STATUS]); - sscanf("8B", "%02X", &FRAME_TYPE_KEYS[TRANSMIT_STATUS]); - sscanf("8D", "%02X", &FRAME_TYPE_KEYS[ROUTE_INFORMATION_PACKET]); - sscanf("8E", "%02X", &FRAME_TYPE_KEYS[AGGREGATE_ADDRESSING_UPDATE]); - sscanf("90", "%02X", &FRAME_TYPE_KEYS[RECEIVE_PACKET]); - sscanf("91", "%02X", &FRAME_TYPE_KEYS[EXPLICIT_RX_INDICATOR]); - sscanf("92", "%02X", &FRAME_TYPE_KEYS[IO_DATA_SAMPLE_RX_INDICATOR]); - sscanf("95", "%02X", &FRAME_TYPE_KEYS[NODE_IDENTIFICATION_INDICATOR]); - sscanf("97", "%02X", &FRAME_TYPE_KEYS[REMOTE_AT_COMMAND_RESPONSE]); + sscanf("08", "%02X", &FRAME_TYPE_KEYS[AT_COMMAND]); + sscanf("09", "%02X", &FRAME_TYPE_KEYS[AT_COMMAND_QUEUE_REGISTER_VALUE]); + sscanf("10", "%02X", &FRAME_TYPE_KEYS[TRANSMIT_REQUEST]); + sscanf("11", "%02X", + &FRAME_TYPE_KEYS[EXPLICIT_ADDRESSING_COMMAND_FRAME]); + sscanf("17", "%02X", &FRAME_TYPE_KEYS[REMOTE_AT_COMMAND]); + sscanf("88", "%02X", &FRAME_TYPE_KEYS[AT_COMMAND_RESPONSE]); + sscanf("8A", "%02X", &FRAME_TYPE_KEYS[MODEM_STATUS]); + sscanf("8B", "%02X", &FRAME_TYPE_KEYS[TRANSMIT_STATUS]); + sscanf("8D", "%02X", &FRAME_TYPE_KEYS[ROUTE_INFORMATION_PACKET]); + sscanf("8E", "%02X", &FRAME_TYPE_KEYS[AGGREGATE_ADDRESSING_UPDATE]); + sscanf("90", "%02X", &FRAME_TYPE_KEYS[RECEIVE_PACKET]); + sscanf("91", "%02X", &FRAME_TYPE_KEYS[EXPLICIT_RX_INDICATOR]); + sscanf("92", "%02X", &FRAME_TYPE_KEYS[IO_DATA_SAMPLE_RX_INDICATOR]); + sscanf("95", "%02X", &FRAME_TYPE_KEYS[NODE_IDENTIFICATION_INDICATOR]); + sscanf("97", "%02X", &FRAME_TYPE_KEYS[REMOTE_AT_COMMAND_RESPONSE]); } //***************************************************************************** void SerialDevice::Read_Frame_Header() { - boost::asio::async_read(serial_port_, - boost::asio::buffer(current_frame_.Get_Frame_Data(), - Xbee::Frame::FRAME_HEADER_LENGTH), - [this](boost::system::error_code error, std::size_t) - { - if (!error) - { - int start_delimiter_position = - current_frame_.Get_Start_Delimiter_Position(); - - if (start_delimiter_position >= 0) - { - if (0 == start_delimiter_position) - current_frame_.Decode_Frame_Header(); - else - { - /* The header is corrupted. */ - boost::asio::async_read(serial_port_, - boost::asio::buffer(current_frame_.Get_Frame_Data(), - start_delimiter_position), - [this](boost::system::error_code error, std::size_t) - { - current_frame_.Rearrange_Corrupted_Header(); - current_frame_.Decode_Frame_Header(); - }); - } + boost::asio::async_read(serial_port_, + boost::asio::buffer(current_frame_.Get_Frame_Data(), + Xbee::Frame::FRAME_HEADER_LENGTH), + [this](boost::system::error_code error, std::size_t) + { + if (!error) + { + int start_delimiter_position = + current_frame_.Get_Start_Delimiter_Position(); - Read_Frame_Body(); - } - else - { - /* The header is totally corrupted, read another header. */ - Read_Frame_Header(); - } - } - else - { - std::cout << "Error Occured:" << std::endl; - std::cout << error << std::endl; - std::cout << "Communication With XBee is Lost." << std::endl; - serial_port_.close(); - } - }); + if (start_delimiter_position >= 0) + { + if (0 == start_delimiter_position) + current_frame_.Decode_Frame_Header(); + else + { + /* The header is corrupted. */ + boost::asio::async_read(serial_port_, + boost::asio::buffer(current_frame_.Get_Frame_Data(), + start_delimiter_position), + [this](boost::system::error_code error, std::size_t) + { + current_frame_.Rearrange_Corrupted_Header(); + current_frame_.Decode_Frame_Header(); + }); + } + + Read_Frame_Body(); + } + else + { + /* The header is totally corrupted, read another header. */ + Read_Frame_Header(); + } + } + else + { + std::cout << "Error Occured:" << std::endl; + std::cout << error << std::endl; + std::cout << "Communication With XBee is Lost." << std::endl; + serial_port_.close(); + } + }); } //***************************************************************************** void SerialDevice::Read_Frame_Body() { - boost::asio::async_read(serial_port_, - boost::asio::buffer(current_frame_.Get_Frame_Body(), - current_frame_.Get_Frame_Body_Length()), - [this](boost::system::error_code error, std::size_t) - { - if (!error) - { - if (current_frame_.Get_Frame_Type() == - FRAME_TYPE_KEYS[RECEIVE_PACKET]) - { - char msg_type = current_frame_.Get_Message_Type(); - std::shared_ptr in_message = - std::make_shared(); - - if (msg_type == 'F') - { - in_message->append(current_frame_.Get_Frame_Body() - + 11, - current_frame_.Get_Frame_Body_Length() - 12); - in_fragments_->Push_Back(in_message); - } - - else if (msg_type == 'A' || msg_type == 'P') - { - in_message->append(current_frame_.Get_Frame_Body(), - current_frame_.Get_Frame_Body_Length() - 1); - in_Acks_and_Pings_->Push_Back(in_message); - } - - else if (msg_type == 'S') - { - in_message->append(current_frame_.Get_Frame_Body() + 12, - current_frame_.Get_Frame_Body_Length() - 13); - in_std_messages_->Push_Back(in_message); - } - } - else if (current_frame_.Get_Frame_Type() == - FRAME_TYPE_KEYS[AT_COMMAND_RESPONSE]) - { - std::shared_ptr in_message = - std::make_shared(); - - in_message->append(current_frame_.Get_Frame_Body() + 1, - current_frame_.Get_Frame_Body_Length() - 2); - - command_responses_->Push_Back(in_message); - } + boost::asio::async_read(serial_port_, + boost::asio::buffer(current_frame_.Get_Frame_Body(), + current_frame_.Get_Frame_Body_Length()), + [this](boost::system::error_code error, std::size_t) + { + if (!error) + { + if (current_frame_.Get_Frame_Type() == FRAME_TYPE_KEYS[RECEIVE_PACKET]) + { + char msg_type = current_frame_.Get_Message_Type(); + std::shared_ptr in_message = + std::make_shared(); - Read_Frame_Header(); - } - else - { - std::cout << "Error Occured:" << std::endl; - std::cout << error << std::endl; - std::cout << "Communication With XBee is Lost." << std::endl; - serial_port_.close(); - } - }); + if (msg_type == FRAGMENT_MSG_ID) + { + in_message->append(current_frame_.Get_Frame_Body() + + 11, + current_frame_.Get_Frame_Body_Length() - 12); + in_fragments_->Push_Back(in_message); + } + + else if (msg_type == ACKNOWLEDGEMENT_MSG_ID || msg_type == PING_MSG_ID) + { + in_message->append(current_frame_.Get_Frame_Body(), + current_frame_.Get_Frame_Body_Length() - 1); + in_Acks_and_Pings_->Push_Back(in_message); + } + + else if (msg_type == STANDARD_MSG_ID) + { + in_message->append(current_frame_.Get_Frame_Body() + 12, + current_frame_.Get_Frame_Body_Length() - 13); + in_std_messages_->Push_Back(in_message); + } + + else if (msg_type == PACKET_LOSS_MSG_ID) + { + in_message->append(current_frame_.Get_Frame_Body() + 11, + current_frame_.Get_Frame_Body_Length() - 12); + in_packet_loss_->Push_Back(in_message); + } + + else + { + // nothing to do + } + } + else if (current_frame_.Get_Frame_Type() == + FRAME_TYPE_KEYS[AT_COMMAND_RESPONSE]) + { + std::shared_ptr in_message = + std::make_shared(); + + in_message->append(current_frame_.Get_Frame_Body() + 1, + current_frame_.Get_Frame_Body_Length() - 2); + + command_responses_->Push_Back(in_message); + } + else if (current_frame_.Get_Frame_Type() == + FRAME_TYPE_KEYS[EXPLICIT_RX_INDICATOR]) + { + std::shared_ptr in_message = + std::make_shared(); + + in_message->append(current_frame_.Get_Frame_Body() + 17, + current_frame_.Get_Frame_Body_Length() - 18); + in_message->insert(in_message->begin(), 'S'); + in_message->insert(in_message->begin(), 'R'); + command_responses_->Push_Back(in_message); + } + + Read_Frame_Header(); + } + else + { + std::cout << "Error Occured:" << std::endl; + std::cout << error << std::endl; + std::cout << "Communication With XBee is Lost." << std::endl; + serial_port_.close(); + } + }); } //***************************************************************************** void SerialDevice::Write_Frame() { - boost::asio::async_write(serial_port_, - boost::asio::buffer(out_messages_.front().data(), - out_messages_.front().size()), - [this](boost::system::error_code error, - std::size_t transferred_bytes) - { - if (!error) - { - out_messages_.pop_front(); - if (!out_messages_.empty()) - Write_Frame(); - } - }); + boost::asio::async_write(serial_port_, + boost::asio::buffer(out_messages_.front().data(), + out_messages_.front().size()), + [this](boost::system::error_code error, + std::size_t transferred_bytes) + { + if (!error) + { + out_messages_.pop_front(); + if (!out_messages_.empty()) + Write_Frame(); + } + }); } //***************************************************************************** bool SerialDevice::Is_IO_Service_Stopped() { - return io_service_.stopped(); + return io_service_.stopped(); } //***************************************************************************** void SerialDevice::Reset_IO_Service() { - io_service_.reset(); -} - - + io_service_.reset(); +} + } diff --git a/src/TestBuzz.cpp b/src/TestBuzz.cpp index 3bcffb9..a846510 100644 --- a/src/TestBuzz.cpp +++ b/src/TestBuzz.cpp @@ -3,84 +3,99 @@ /* September 20, 2016 -- @Copyright Aymen Soussia. All rights reserved. */ /* (aymen.soussia@gmail.com) */ - #include -#include -#include +#include +#include #include +#include "mavros_msgs/ParamGet.h" #include - - //***************************************************************************** -void Receive_Payload_Callback(const mavros_msgs::Mavlink::ConstPtr& mavlink_msg) -{ - std::cout << "Received Mavlink Message:" << std::endl; - for (unsigned short i = 0; i < mavlink_msg->payload64.size(); i++) - std::cout << mavlink_msg->payload64.at(i) << std::endl; - std::cout << std::endl; +void Receive_Payload_Callback( + const mavros_msgs::Mavlink::ConstPtr &mavlink_msg) { + std::cout << "Received Mavlink Message:" << std::endl; + for (unsigned short i = 0; i < mavlink_msg->payload64.size(); i++) + std::cout << mavlink_msg->payload64.at(i) << std::endl; + std::cout << std::endl; } - //***************************************************************************** -unsigned int Get_Random_Size(unsigned int min, unsigned int max) -{ - return rand() % (max - min) + min; +unsigned int Get_Random_Size(unsigned int min, unsigned int max) { + return rand() % (max - min) + min; } - //***************************************************************************** -unsigned long long Get_Random_Int64(unsigned long long min, unsigned long long max) -{ - return rand() % (max - min) + min; +unsigned long long Get_Random_Int64(unsigned long long min, + unsigned long long max) { + return rand() % (max - min) + min; } +//***************************************************************************** +void Init_Random_Seed() { srand(time(NULL)); } //***************************************************************************** -void Init_Random_Seed() -{ - srand (time(NULL)); -} +int main(int argc, char **argv) { + const unsigned int MIN_PAYLOAD_SIZE = 1; + const unsigned int MAX_PAYLOAD_SIZE = 5; + const int DEFAULT_RATE = 10; + int rate = DEFAULT_RATE; - -//***************************************************************************** -int main(int argc, char **argv) -{ - const unsigned int MIN_PAYLOAD_SIZE = 750; - const unsigned int MAX_PAYLOAD_SIZE = 752; - ros::init(argc, argv, "test_buzz"); ros::NodeHandle node_handle; - ros::Publisher mavlink_pub = node_handle.advertise("outMavlink", 1000); - ros::Subscriber mavlink_sub = node_handle.subscribe("inMavlink", 1000, Receive_Payload_Callback); + ros::Publisher mavlink_pub = + node_handle.advertise("outMavlink", 1000); + ros::Subscriber mavlink_sub = + node_handle.subscribe("inMavlink", 1000, Receive_Payload_Callback); + + mavros_msgs::Mavlink mavlink_msg_; + mavlink_msg_.msgid = 1; + if (argc > 1) { + try + { + rate = atoi(argv[1]); + } + catch (...) + { + rate = DEFAULT_RATE; + } + } + + ros::ServiceClient xbeestatus_srv; + xbeestatus_srv = node_handle.serviceClient("/network_status"); + mavros_msgs::ParamGet::Request robot_id_srv_request; robot_id_srv_request.param_id="id"; + mavros_msgs::ParamGet::Response robot_id_srv_response; + while(!xbeestatus_srv.call(robot_id_srv_request,robot_id_srv_response)){ + ros::Duration(0.1).sleep(); + ROS_WARN("Waiting for Xbee to respond to get device ID"); + } + mavlink_msg_.sysid=robot_id_srv_response.value.integer; + + ros::Rate loop_rate(rate); Init_Random_Seed(); int count = 0; const std::size_t MAX_BUFFER_SIZE = 64; char line[MAX_BUFFER_SIZE]; - + std::cout << "Press Enter to Send New Mavlink Message..." << std::endl; - + while (ros::ok() && std::cin.getline(line, MAX_BUFFER_SIZE)) { - mavros_msgs::Mavlink mavlink_msg_; - mavlink_msg_.sysid = 2; - mavlink_msg_.msgid = 1; - unsigned int payload_size = Get_Random_Size(MIN_PAYLOAD_SIZE, MAX_PAYLOAD_SIZE); + unsigned int payload_size = + Get_Random_Size(MIN_PAYLOAD_SIZE, MAX_PAYLOAD_SIZE); + mavlink_msg_.payload64.clear(); - for (unsigned int i = 0; i < payload_size; i++) - { + for (unsigned int i = 0; i < payload_size; i++) { mavlink_msg_.payload64.push_back(Get_Random_Int64(1, ULLONG_MAX)); } std::cout << "Sent Mavlink Message " << count << std::endl; - for (unsigned int i = 0; i < payload_size; i++) - { + for (unsigned int i = 0; i < payload_size; i++) { std::cout << mavlink_msg_.payload64.at(i) << std::endl; } @@ -89,6 +104,7 @@ int main(int argc, char **argv) mavlink_pub.publish(mavlink_msg_); ros::spinOnce(); + loop_rate.sleep(); count++; std::cout << "Press Enter to Send New Mavlink Message..." << std::endl; diff --git a/src/TestBuzzCyclic.cpp b/src/TestBuzzCyclic.cpp new file mode 100644 index 0000000..d808e76 --- /dev/null +++ b/src/TestBuzzCyclic.cpp @@ -0,0 +1,114 @@ +/* RosBuzz.cpp -- Basic ROS Buzz node -- */ +/* ------------------------------------------------------------------------- */ +/* September 20, 2016 -- @Copyright Aymen Soussia. All rights reserved. */ +/* (aymen.soussia@gmail.com) */ + +#include +#include +#include + +#include +#include "mavros_msgs/ParamGet.h" +#include + +//***************************************************************************** +void Receive_Payload_Callback( + const mavros_msgs::Mavlink::ConstPtr &mavlink_msg) { + std::cout << "Received Mavlink Message:" << std::endl; + for (unsigned short i = 0; i < mavlink_msg->payload64.size(); i++) + std::cout << mavlink_msg->payload64.at(i) << std::endl; + std::cout << std::endl; +} + +//***************************************************************************** +unsigned int Get_Random_Size(unsigned int min, unsigned int max) { + return rand() % (max - min) + min; +} + +//***************************************************************************** +unsigned long long Get_Random_Int64(unsigned long long min, + unsigned long long max) { + return rand() % (max - min) + min; +} + +//***************************************************************************** +void Init_Random_Seed() { srand(time(NULL)); } + +//***************************************************************************** +int main(int argc, char **argv) { + const unsigned int MIN_PAYLOAD_SIZE = 10; + const unsigned int MAX_PAYLOAD_SIZE = 32; + const int DEFAULT_RATE = 10; + int rate = DEFAULT_RATE; + + ros::init(argc, argv, "test_buzz"); + + ros::NodeHandle node_handle; + ros::Publisher mavlink_pub = + node_handle.advertise("outMavlink", 1000); + ros::Subscriber mavlink_sub = + node_handle.subscribe("inMavlink", 1000, Receive_Payload_Callback); + + mavros_msgs::Mavlink mavlink_msg_; + mavlink_msg_.msgid = 1; + if (argc > 1) { + try + { + rate = atoi(argv[1]); + } + catch (...) + { + rate = DEFAULT_RATE; + } + } + + ros::ServiceClient xbeestatus_srv; + xbeestatus_srv = node_handle.serviceClient("network_status"); + mavros_msgs::ParamGet::Request robot_id_srv_request; robot_id_srv_request.param_id="id"; + mavros_msgs::ParamGet::Response robot_id_srv_response; + while(!xbeestatus_srv.call(robot_id_srv_request,robot_id_srv_response)){ + ros::Duration(0.1).sleep(); + ROS_WARN("Waiting for Xbee to respond to get device ID"); + } + mavlink_msg_.sysid=robot_id_srv_response.value.integer; + + ros::Rate loop_rate(rate); + + Init_Random_Seed(); + + int count = 0; + // const std::size_t MAX_BUFFER_SIZE = 64; + // char line[MAX_BUFFER_SIZE]; + + std::cout << "Press Enter to Send New Mavlink Message..." << std::endl; + + while (ros::ok()) //&& std::cin.getline(line, MAX_BUFFER_SIZE)) + { + + unsigned int payload_size = + Get_Random_Size(MIN_PAYLOAD_SIZE, MAX_PAYLOAD_SIZE); + mavlink_msg_.payload64.clear(); + + for (unsigned int i = 0; i < payload_size; i++) { + mavlink_msg_.payload64.push_back(Get_Random_Int64(1, ULLONG_MAX)); + } + + std::cout << "Sent Mavlink Message " << count << std::endl; + + /*for (unsigned int i = 0; i < payload_size; i++) { + std::cout << mavlink_msg_.payload64.at(i) << std::endl; + }*/ + + std::cout << std::endl; + + mavlink_pub.publish(mavlink_msg_); + + ros::spinOnce(); + loop_rate.sleep(); + + count++; + // std::cout << "Press Enter to Send New Mavlink Message..." << std::endl; + } + + return 0; +} diff --git a/src/XBeeSetup.cpp b/src/XBeeSetup.cpp new file mode 100644 index 0000000..f19479b --- /dev/null +++ b/src/XBeeSetup.cpp @@ -0,0 +1,70 @@ +/* ---------------------------------------------------------------- + * File: XBeeSetup.cpp + * Date: 02/06/2017 + * Author: Pierre-Yves Breches + * Description: Implementation of the xbeeSetup function to + * configure the xbee module + * Copyright Humanitas Solutions. All rights reserved. + ------------------------------------------------------------------ */ + +#include "XBeeSetup.h" + +bool setupXBee(const std::string &device_port, const unsigned int baud_rate) { + XBeeModule xbee_module; + XMLConfigParser config_parser; + + if (xbee_module.Init_Port(device_port, baud_rate)) { + std::thread th_service(&XBeeModule::Run_Service, &xbee_module); + + while (!xbee_module.Is_Connected() && + !xbee_module.Check_Time_Out_Exceeded()) { + continue; + } + + if (xbee_module.Is_Connected()) { + std::cout << "Connected to XBee." << std::endl; + std::cout << "Loading Config File..." << std::endl; + + if (config_parser.Load_Config()) { + std::cout << "Config Loaded Successfully." << std::endl; + std::cout << "Transferring Data..." << std::endl; + std::vector *config_parameters = + config_parser.Get_Loaded_Parameters(); + + for (std::size_t i = 0; i < config_parameters->size(); i++) { + std::string current_command; + xbee_module.Format_AT_Command(config_parameters->at(i), + ¤t_command); + xbee_module.Send_Data(current_command); + } + + std::string write_command = "ATWR \r"; + xbee_module.Send_Data(write_command); + } + } + + th_service.join(); + + std::cout << "Exiting AT Command Mode..." << std::endl; + + if (xbee_module.Is_Connected()) + { + xbee_module.Exit_AT_Command_Mode(); + + if (config_parser.Is_Config_Loaded_Successfully()) + { + std::cout << "XBee Configured Successfully." << std::endl; + return true; + } + else + { + std::cout << "XBee Configuration Failed." << std::endl; + } + } + else + { + std::cout << "XBee Configuration Failed." << std::endl; + } + } + return false; +} diff --git a/src/Xbee.cpp b/src/Xbee.cpp index 53b2669..51448a5 100644 --- a/src/Xbee.cpp +++ b/src/Xbee.cpp @@ -3,62 +3,73 @@ /* September 20, 2016 -- @Copyright Aymen Soussia. All rights reserved. */ /* (aymen.soussia@gmail.com) */ - +#include "XBeeSetup.h" #include "CommunicationManager.h" - +#include //***************************************************************************** -int main(int argc, char* argv[]) -{ +int main(int argc, char *argv[]) { - try - { - ros::init(argc, argv, "xbee"); - ros::NodeHandle node_handle; + try { + ros::init(argc, argv, "xbee"); - Mist::Xbee::CommunicationManager communication_manager; - std::string device; - double baud_rate; - Mist::Xbee::CommunicationManager::DRONE_TYPE drone_type = - Mist::Xbee::CommunicationManager::DRONE_TYPE::SLAVE; - Mist::Xbee::CommunicationManager::RUNNING_MODE running_mode = - Mist::Xbee::CommunicationManager::RUNNING_MODE::SOLO; + Mist::Xbee::CommunicationManager communication_manager; + std::string device; + double baud_rate; + Mist::Xbee::CommunicationManager::DRONE_TYPE drone_type = + Mist::Xbee::CommunicationManager::DRONE_TYPE::SLAVE; + Mist::Xbee::CommunicationManager::RUNNING_MODE running_mode = + Mist::Xbee::CommunicationManager::RUNNING_MODE::SOLO; - if (argc > 1) - { - if (!strcmp(argv[1], "master")) - drone_type = Mist::Xbee::CommunicationManager::DRONE_TYPE::MASTER; + if (argc > 1) { + if (!strcmp(argv[1], "master")) + drone_type = Mist::Xbee::CommunicationManager::DRONE_TYPE::MASTER; - if (argc > 2) - { - if (!strcmp(argv[2], "swarm")) - running_mode = Mist::Xbee::CommunicationManager::RUNNING_MODE::SWARM; - } - } - if (!node_handle.getParam("USB_port", device)) - { - std::cout << "Failed to Get Topic Name: param 'USB_port' Not Found." << std::endl; - return EXIT_FAILURE; - } + if (argc > 2) { + if (!strcmp(argv[2], "swarm")) + running_mode = Mist::Xbee::CommunicationManager::RUNNING_MODE::SWARM; + } + } - if (!node_handle.getParam("Baud_rate", baud_rate)) - { - std::cout << "Failed to Get Topic Name: param 'Baud_rate' Not Found." << std::endl; - return EXIT_FAILURE; - } - if (communication_manager.Init(device, static_cast(baud_rate))) - communication_manager.Run(drone_type, running_mode); + ros::NodeHandle node_handle; + + if (!node_handle.getParam("USB_port", device)) + { + std::cout << "Failed to Get Topic Name: param 'USB_port' Not Found." << std::endl; + return EXIT_FAILURE; + } + + if (!node_handle.getParam("Baud_rate", baud_rate)) + { + std::cout << "Failed to Get Topic Name: param 'Baud_rate' Not Found." << std::endl; + return EXIT_FAILURE; + } + + //setupXBee(device, static_cast(baud_rate)); + + std::cout << "Going to init !!!!" << std::endl; + + if (communication_manager.Init(device, static_cast(baud_rate))) + { + communication_manager.Run(drone_type, running_mode); + } } - catch (const std::exception& e) + catch (const std::exception &e) { - std::cout << "Error Occured:" << std::endl; - std::cout << e.what() << std::endl; + std::cout << "Error: " << e.what() << std::endl; + std::cout << "Please Try One of The Following Options:" << std::endl; + std::cout << " 1) Change The Baud Rate. Make Sure It Matches The Current Baud Rate Used by The XBee (By default BD = 9600 bps)." << std::endl; + std::cout << " 2) Change The Specified Device (e.g. COM1 for Windows or /dev/tty/USB0 for Linux)." << std::endl; + std::cout << " 3) Disconnect and Connect The XBee." << std::endl; + std::cout << " 4) Press The Reset Button on The XBee." << std::endl; + std::cout << " 5) Update The Firmware With XCTU." << std::endl; + std::cout << "XBee Configuration Failed." << std::endl; } catch (...) { - std::cout << "Unexpected Fatal Error." << std::endl; - std::cout << "Communication With XBee is Lost." << std::endl; - return EXIT_FAILURE; + std::cout << "Unexpected Fatal Error." << std::endl; + std::cout << "Communication With XBee is Lost." << std::endl; + return EXIT_FAILURE; } std::cout << std::endl; diff --git a/src/frame_generators.cpp b/src/frame_generators.cpp new file mode 100644 index 0000000..6661a96 --- /dev/null +++ b/src/frame_generators.cpp @@ -0,0 +1,169 @@ +/* ---------------------------------------------------------------- + * File: frame_generators.cpp + * Created on: 21/06/2017 + * Author: Pierre-Yves Breches + * Description: This file contains functions used for the the creation of xbee + * frame + * Copyright Humanitas Solutions. All rights reserved. + ------------------------------------------------------------------ */ + +#include "frame_generators.h" + +namespace Mist +{ + +namespace Xbee +{ + void Generate_Transmit_Request_Frame( + const char* message, + std::string * frame, + const std::size_t message_size, + const unsigned char frame_ID, + const std::string& destination_adssress, + const std::string& short_destination_adress, + const std::string& broadcast_radius, + const std::string& options) + /* Description: Generate a link testing frame as presented page 73-74 + * in Ressources/XbeeModule_Datasheet.pdf + ------------------------------------------------------------------ */ + { + const unsigned char FRAME_TYPE = static_cast(0x10); /* Transmit Request Frame */ + std::string frame_parameters; + std::string bytes_frame_parameters; + + frame_parameters.append(destination_adssress); + frame_parameters.append(short_destination_adress); + frame_parameters.append(broadcast_radius); + frame_parameters.append(options); + + Convert_HEX_To_Bytes(frame_parameters, &bytes_frame_parameters); + + frame->push_back(FRAME_TYPE); + frame->push_back(frame_ID); + frame->append(bytes_frame_parameters); + frame->append(message, message_size); + + Calculate_and_Append_Checksum(frame); + Add_Length_and_Start_Delimiter(frame); + } + + void generateLinkTestingFrame(std::string* frame, + uint16_t rssi_payload_size, + uint16_t rssi_iterations, + std::string device_64_bits_address, + uint64_t target_64_bits_address) + /* Description: Generate a link testing frame as presented page 29-30 + * in Ressources/XbeeModule_Datasheet.pdf + ------------------------------------------------------------------ */ + { + static const unsigned char FRAME_TYPE = static_cast(0x11); + static const unsigned char FRAME_ID = static_cast(0x01); + static const std::string link_testing_params = "FFFEE6E60014C1050000"; + + std::string frame_parameters; + std::string bytes_frame_parameters; + + frame_parameters = link_testing_params; + frame_parameters += int_to_hex(target_64_bits_address, 16); + frame_parameters += int_to_hex(rssi_payload_size, 4); // packet size for testing + frame_parameters += int_to_hex(rssi_iterations, 4); // number of iterations + + Convert_HEX_To_Bytes(frame_parameters, &bytes_frame_parameters); + + frame->push_back(FRAME_TYPE); + frame->push_back(FRAME_ID); + frame->append(device_64_bits_address); + frame->append(bytes_frame_parameters); + + Calculate_and_Append_Checksum(frame); + Add_Length_and_Start_Delimiter(frame); + } + + + void Generate_AT_Command(const char* command, + std::string* frame, + const unsigned char frame_ID) + /* Description: Generate an AT command frame as decribed page 73 + * in Ressources/XbeeModule_Datasheet.pdf + ------------------------------------------------------------------ */ + { + const unsigned char FRAME_TYPE = static_cast(0x09);/* AT Command Frame */ + std::string temporary_parameter_value; + + frame->push_back(FRAME_TYPE); + frame->push_back(frame_ID); + frame->append(command); + + Calculate_and_Append_Checksum(frame); + Add_Length_and_Start_Delimiter(frame); + } + + void Convert_HEX_To_Bytes(const std::string& HEX_data, + std::string* converted_data) + /* Description: + * + ------------------------------------------------------------------ */ + { + const unsigned short TWO_BYTES = 2; + char temporary_buffer[TWO_BYTES]; + unsigned char temporary_char; + int temporary_HEX; + + for (unsigned short i = 0; i <= HEX_data.size() - TWO_BYTES; + i += TWO_BYTES) + { + memcpy(temporary_buffer, HEX_data.c_str() + i, TWO_BYTES); + sscanf(temporary_buffer, "%02X", &temporary_HEX); + temporary_char = static_cast(temporary_HEX); + converted_data->push_back(temporary_char); + } + } + + void Calculate_and_Append_Checksum(std::string* frame) + /* Description: + * + ------------------------------------------------------------------ */ + { + unsigned short bytes_sum = 0; + unsigned lowest_8_bits = 0; + unsigned short checksum = 0; + unsigned char checksum_byte; + + for (unsigned short i = 0; i < frame->size(); i++) + bytes_sum += static_cast(frame->at(i)); + + lowest_8_bits = bytes_sum & 0xFF; + checksum = 0xFF - lowest_8_bits; + checksum_byte = static_cast(checksum); + frame->push_back(checksum_byte); + } + + + void Add_Length_and_Start_Delimiter(std::string* frame) + /* Description: + * + ------------------------------------------------------------------ */ + { + const unsigned short FIVE_BYTES = 5; + const unsigned char START_DLIMITER = static_cast(0x7E); + char temporary_buffer[FIVE_BYTES]; + unsigned char temporary_char; + int Hex_frame_length_1; + int Hex_frame_length_2; + std::string header; + int frame_length = frame->size() - 1; /* frame_length = frame_size - checksum byte */ + + header.push_back(START_DLIMITER); + sprintf(temporary_buffer, "%04X", frame_length); + sscanf(temporary_buffer, "%02X%02X", &Hex_frame_length_1, + &Hex_frame_length_2); + temporary_char = static_cast(Hex_frame_length_1); + header.push_back(temporary_char); + temporary_char = static_cast(Hex_frame_length_2); + header.push_back(temporary_char); + frame->insert(0, header); + } + +} + +} diff --git a/src/main.cpp b/src/main.cpp index 97bb2de..fc6a1b1 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -3,112 +3,49 @@ /* November 30, 2016 -- @Copyright Aymen Soussia. All rights reserved. */ /* (aymen.soussia@gmail.com) */ - -#include - -#include"XBeeModule.h" -#include"XMLConfigParser.h" - - -//***************************************************************************** -void Setup_XBee(const std::string& device_port, const unsigned int baud_rate) -{ - XBeeModule xbee_module; - XMLConfigParser config_parser; - - if (xbee_module.Init_Port(device_port, baud_rate)) - { - std::thread th_service(&XBeeModule::Run_Service, &xbee_module); - - while (!xbee_module.Is_Connected() && !xbee_module.Check_Time_Out_Exceeded()) - { - continue; - } - - if (xbee_module.Is_Connected()) - { - std::cout << "Connected to XBee." << std::endl; - std::cout << "Loading Config File..." << std::endl; - - if (config_parser.Load_Config()) - { - std::cout << "Config Loaded Successfully." << std::endl; - std::cout << "Transferring Data..." << std::endl; - std::vector* config_parameters = config_parser.Get_Loaded_Parameters(); - - for (std::size_t i = 0; i < config_parameters->size(); i++) - { - std::string current_command; - xbee_module.Format_AT_Command(config_parameters->at(i), ¤t_command); - xbee_module.Send_Data(current_command); - } - - std::string write_command = "ATWR \r"; - xbee_module.Send_Data(write_command); - } - } - - th_service.join(); - - std::cout << "Exiting AT Command Mode..." << std::endl; - - if (xbee_module.Is_Connected()) - { - xbee_module.Exit_AT_Command_Mode(); - - if (config_parser.Is_Config_Loaded_Successfully()) - std::cout << "XBee Configured Successfully." << std::endl; - else - std::cout << "XBee Configuration Failed." << std::endl; - } - else - { - std::cout << "XBee Configuration Failed." << std::endl; - } - } -} +#include "XBeeSetup.h" //***************************************************************************** int main(int argc, char*argv[]) { - try - { - std::string device_port; - unsigned int baud_rate = 0; - const unsigned int DEFAULT_BAUD_RATE = 9600; - const std::string DEFAULT_DEVICE_PORT = "/dev/ttyUSB0"; + try + { + std::string device_port; + unsigned int baud_rate = 0; + const unsigned int DEFAULT_BAUD_RATE = 9600; + const std::string DEFAULT_DEVICE_PORT = "/dev/ttyUSB0"; - if (argc < 1) - device_port = DEFAULT_DEVICE_PORT; - else - device_port.append(argv[1]); + if (argc < 1) + device_port = DEFAULT_DEVICE_PORT; + else + device_port.append(argv[1]); - if (argc < 2) - baud_rate = DEFAULT_BAUD_RATE; - else - sscanf(argv[2], "%u", &baud_rate); + if (argc < 2) + baud_rate = DEFAULT_BAUD_RATE; + else + sscanf(argv[2], "%u", &baud_rate); - Setup_XBee(device_port, baud_rate); - } - catch (const std::exception& e) - { - std::cout << "Error: " << e.what() << std::endl; - std::cout << "Please Try One of The Following Options:" << std::endl; - std::cout << " 1) Change The Baud Rate. Make Sure It Matches The Current Baud Rate Used by The XBee (By default BD = 9600 bps)." << std::endl; - std::cout << " 2) Change The Specified Device (e.g. COM1 for Windows or /dev/tty/USB0 for Linux)." << std::endl; - std::cout << " 3) Disconnect and Connect The XBee." << std::endl; - std::cout << " 4) Press The Reset Button on The XBee." << std::endl; - std::cout << " 5) Update The Firmware With XCTU." << std::endl; - std::cout << "XBee Configuration Failed." << std::endl; + //setupXBee(device_port, baud_rate); + } + catch (const std::exception& e) + { + std::cout << "Error: " << e.what() << std::endl; + std::cout << "Please Try One of The Following Options:" << std::endl; + std::cout << " 1) Change The Baud Rate. Make Sure It Matches The Current Baud Rate Used by The XBee (By default BD = 9600 bps)." << std::endl; + std::cout << " 2) Change The Specified Device (e.g. COM1 for Windows or /dev/tty/USB0 for Linux)." << std::endl; + std::cout << " 3) Disconnect and Connect The XBee." << std::endl; + std::cout << " 4) Press The Reset Button on The XBee." << std::endl; + std::cout << " 5) Update The Firmware With XCTU." << std::endl; + std::cout << "XBee Configuration Failed." << std::endl; - } - catch (...) - { - std::cout << " Unexpected Error." << std::endl; - std::cout << "XBee Configuration Failed." << std::endl; - return EXIT_FAILURE; - } + } + catch (...) + { + std::cout << " Unexpected Error." << std::endl; + std::cout << "XBee Configuration Failed." << std::endl; + return EXIT_FAILURE; + } - return EXIT_SUCCESS; + return EXIT_SUCCESS; }